우리는 방이 어두울 때 조명을 킨다. 조명은 우리의 시야를 밝혀주는 기능을 하고 있는 셈이다.
그런데 우리가 외출을 한다고해보자. 우리는 밖에 있는 동안엔 조명의 기능이 필요 없기 때문에 불을 끄고 외출 할 것이다.
그리고 다시 저녁에 돌아오면 조명을 다시 켠다.
이렇듯 로봇에도 수많은 기능들(주행, 주변 지도 그리기, 위치 찾기, 주변 인식하기, 장애물 피하기 등등) 들이 있지만 이 모든 기능들이 항상 필요한 건 아니다.
예를 들어 삼성 로봇 청소기를 생각해보자.
영상에서 와 같이 로봇은 주변의 파악하는 기능이 필요하다.
이 기능은 지도를 그리는 것인데 어떻게 지도가 그려지는지 참고하고 싶은 사람은 이 영상을 보기바란다.
이렇게 로봇이 지도를 그리는 과정은 청소를 하기 전에 한 번만 필요하다.
그렇기 때문에 한 번 지도를 작성하고 나선 그 기능을 담당하는 node를 꺼줘야한다.
그래야 로봇의 에너지를 절약할 수 있기 때문이다.
오늘은 이렇듯 특정 기능을 담당하는 node의 상태(꺼졌다, 켜졌다 등)를 정의하고 그 상태를 바꿀 수(껐다, 켰다 등) 있는 lifecycle node에 대해서 배우고 구현해보도록 하자.
State machine
Lifecycle
state machine으로 묘사한 시스템의 상태를 관리하고 제어하는 기능을 제공하는 ROS2의 프레임워크(기능과 도구)이다.
위에서 들었던 지도 그리는 node를 생각하면 상태가 1.꺼짐 2. 켜짐이 있었다.
ROS2의 lifecycle을 이용하면 해당 node가 꺼져있는지, 켜져있는지 상태를 확인 할 수 있다.
또한 현재 상태를 확인한 후 원하는 상태(꺼져있다면 켜고, 켜져있다면 끄는 등)로 변경시킬 수 있다.
하단의 그림은 ROS2에서 lifecycle 기능으로 관리 및 제어 가능한 node의 state machine이다. 뭐가 많아 보이는데 끄고 켜는걸 좀 더 세세하게 나눴을 뿐 본질은 어렵지 않다. 하나하나 살펴보자. 참고로 안외워도 되고 구현해야되는데 생각 안날 때 밑에 그림 다시 찾아서 천천히 구현하면 된다.
node 상태를 나타내는 용어
상태를 변화시키는 행위를 나타내는 용어
상태 변화동안을 묘사하는 용어
Lifecycle node
이번엔 simple_lifecycle_pkg라는 이름으로 패키지를 만들어보자.
mkdir -p simple_lifecycle_ws/src
cd simple_lifecycle_ws/src
ros2 pkg create --build-type ament_cmake --license Apache-2.0 simple_lifecycle_pkg
cd simple_lifecycle_pkg
code .
패키지 내부 경로로 이동해서 visual code까지 열어줬다.
자 그 다음 우리 talker lifecycle node를 작성해야한다.
이 node는 우리가 일전에 pub/sub 구현 실습
에서 작성한 것과 매우 유사한 기능을 가지고 있다.(살짝 출력하는 log는 지도 작성 기능 예시에 맞게 변경했다.)
먼저 소스코드를 작성할 파일, lifecycle_talker.cpp을 다음과 같이 생성해주자.
그다음 내부에 다음 코드를 먼저 복사 붙여넣기 하자. 항상 말하지만 나중에 스스로 구현해야되면 이 코드를 reference삼아 구성요소 및 흐름을 이해하고 있다고 써먹으면 된다.
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
using namespace std::chrono_literals;
// class MinimalPublisher : public rclcpp::Node
class MinimalPublisher : public rclcpp_lifecycle::LifecycleNode
{
public:
MinimalPublisher()
// : Node("minimal_publisher"), count_(0)
: rclcpp_lifecycle::LifecycleNode("minimal_publisher"), count_(0)
{
// publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
// timer_ = this->create_wall_timer(
// 500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State &state)
{
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
timer_ = this->create_wall_timer(1s, std::bind(&MinimalPublisher::timer_callback, this));
RCUTILS_LOG_INFO_NAMED(get_name(), "on_configure() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State &state)
{
publisher_->on_activate();
RCUTILS_LOG_INFO_NAMED(get_name(), "on_activate() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state)
{
publisher_->on_deactivate();
RCUTILS_LOG_INFO_NAMED(get_name(), "on_deactivate() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state)
{
timer_.reset();
publisher_.reset();
RCUTILS_LOG_INFO_NAMED(get_name(), "on cleanup is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state)
{
timer_.reset();
publisher_.reset();
RCUTILS_LOG_INFO_NAMED(get_name(), "on shutdown is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
private:
void timer_callback()
{
auto message = std_msgs::msg::String();
message.data = "Creating a map " + std::to_string(count_++);
// Print the current state for demo purposes
if (!publisher_->is_activated())
{
RCLCPP_INFO(
get_logger(), "Lifecycle publisher is currently inactive. Messages are not published.");
}
else
{
RCLCPP_INFO(get_logger(), "Lifecycle publisher is active. Publishing: [%s]", message.data.c_str());
}
// We independently from the current state call publish on the lifecycle
// publisher.
// Only if the publisher is in an active state, the message transfer is
// enabled and the message actually published.
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>> publisher_;
size_t count_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
std::shared_ptr<MinimalPublisher> minimal_publisher = std::make_shared<MinimalPublisher>();
rclcpp::spin(minimal_publisher->get_node_base_interface());
// rclcpp::spin(std::make_shared<MinimalPublisher>()); //origianl
rclcpp::shutdown();
return 0;
}
자 이제 코드 분석을 해보자.
먼저 필요한 헤더파일들은 표준 라이브러리와 ROS2에서 include하고 있다.
나머지는 전부다 일반 talker node를 만들 때 배웠던 거라 익숙하지만
#include "rclcpp_lifecycle/lifecycle_node.hpp"
는 처음본다.
해당 헤더파일은 일반 node가 아닌 lifecycle node라는 것을 만들 때 필요한 헤더파일이다.
추후 어디서 어떻게 사용하기 위해 include된 것 인지 나머지 코드를 보면서 직접 살펴보자.
위의 코드를 보면 기존의 Node를 상속 받던 부분, publisher와 timer를 생성하는 부분이 class 생성자(constructor) 부분에서 빠진 것을 볼 수 있다.
...
// : Node("minimal_publisher"), count_(0)
...
// publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
// timer_ = this->create_wall_timer(
// 500ms, std::bind(&MinimalPublisher::timer_callback, this));
대신 rclcpp_lifecycle::LifecycleNode를 상속받고 있는데 lifecycle node는 일반 node와 다르게 해당 node의 상태를 확인할 수 있고 제어할 수 있는 기능을 갖는다.
Publisher와 timer 생성은 해당 class의 method인 on_configure에서 생성될 예정이다.
앞서 용어 설명에서 on_configure는 unconfigure 상태에서 inactive 상태로 변환 시켜주는 기능을 한다고 배웠다.
즉, publisher/subscriber, timer, service 등을 생성하는 역할을 담당한다.
그렇기 때문에 MinimalPublisher class의 onconfigure() method는 publisher와 timer를 만들고 있다.
만드는 방식은 일반 node와 다르지 않지만 여기서 "publisher"는 그 타입이 일반 publisher가 아닌데 밑에서 해당 타입을 정의하는 부분에서 살펴볼 에정이다.
그리고 on_configure()가 성공적으로 동작했으면 성공했다는
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS
를 반환한다.
on_activate()의 경우 inactive에서 active로 lifecycle node의 상태를 변환한다. active상태에서는 실제로 publisher/subscriber 등이 데이터를 생성 및 처리하고 service 호출에 응답하는 등의 실질 적인 기능이 동작해야한다.
이 lifecycle node의 경우 publihser를 on_active()라는 method를 통해서 실질적으로 publisher가 메세지를 발행할 수 있는 상태가 될 수 있도록 활성화 시키고 있다.
이 on_active()가 어떤 영향을 끼치는지는 timer callback을 살펴볼 때 살펴볼 예정이다.
그리고 on_activate()가 성공적으로 동작했으면 성공했다는
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS
를 반환한다.
on_deactivate()의 경우 active에서 inactive로 node의 상태를 변화 시킨다.
inactive상태에서는 publisher/subscriber, service등이 동작하지 않아야 하기 때문에 publisher_를 on_deactive()를 통해서 비활성화한다.
이렇게 비활성화 되면 timer callback에서 publisher_를 통해 message 발생 명령을 내려도 실제로 그 기능을 하지 못 한다.
그리고 on_deactivate()가 성공적으로 동작했으면 성공했다는
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS
를 반환한다.
on_cleanup()은 re-configure를 하기 전에 생성되었던 publisher/subscriber, service, 필요없는 변수들을 청소하는 작업을 한다. 또한 node 상태를 inactive에서 unconfigured로 변경한다.
따라서 코드에서는 이전에 생성했던 timer와 publisher의 메모리를 해제하고 있다.
그리고 on_cleanup()가 성공적으로 동작했으면 성공했다는
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS
를 반환한다.
on_shutdown()은 unconfigured, inactive, active 상태에서 호출 될 수 있으므로 node가 기능을 잃기전 안전하게 필요없는 메모리를 해제해줘야하는 역할을 수행해야한다.
그렇기 때문에 다소 on_cleanup()과 유사해보일 수 있다.
해당 코드에서는 일전에 생성되어있을 수 있었던 timer, publisher의 메모리를 해제한다.
그리고 on_shutdown()가 성공적으로 동작했으면 성공했다는
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS
를 반환한다.
publsher_의 publisher를 생성할 때 등록해줘야하는 timer_callback이 정상적으로 동작하기 위해서 private 접근 지정자에서 정의해줘야한다.
해당 timer_callback 코드에서는
메세지를 발행할 때 필요한 publisher, timer, count 변수들을 선언한다.
한가지 특이한건 publisher_의 타입이
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>>
라는 것이다.
이렇게 on_active, on_deactive으로 활성화/비활성화 할 수 있는 publisher를 만들기 위해서는 rclcpp_lifecycle 헤더로부터 LifecyclePublisher라는 타입을 사용해야한다.
이제 node가 executable을 실행했을 때 동작할 수 있도록 main함수를 작성해야 한다.
여기서 독특한 점은 rclcpp spin을 사용할 때 이전처럼 class 자체를 넣어주는게 아니라 node의 base interface를 획득하여 넣어준다.
이렇게 하는 이유는 lifecycle node 특성상 노드의 상태를 관찰 및 제어하는데 그 제어권등을 get_node_base_interface로 획득해서 spin으로 넘겨줘야 하기 때문이다.
소스코드 작성이 끝났으면 다음 함수들을 CMakeLists.txt에 추가해주자.
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
add_executable(lifecycle_talker src/lifecycle_talker.cpp)
ament_target_dependencies(lifecycle_talker rclcpp std_msgs rclcpp_lifecycle)
install(TARGETS
lifecycle_talker
DESTINATION lib/${PROJECT_NAME})
(예시)
여기서 주목할 점은 우리는 lifecycle node와 lifecycle publisher를 사용했기 때문에 해당 타입을 갖고 있는 "rclcpp_lifecycle" 패키지를 찾고 executable을 생성할 때 dependency로 넣어줬다는 것이다.
dependency 이야기를 하니 생각나는게 있는가?
그렇다 package.xml도 수정해주자!
다음 코드를 추가해주자.
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<build_depend>rclcpp_lifecycle</build_depend>
(예시)
rclcpp와 std_msgs는 일전에 봤던 것과 같다.
그런데 dependency로 rclcpp_lifecycle을 추가해줬다.
대망의 빌드 시간이다.
다음과 같이 colcon build해주자.
cd ~/simple_lifecycle_ws
colcon build
빌드가 완료되면 실행하자.
cd ~/simple_lifecycle_ws
source install/setup.bash
ros2 run simple_lifecycle_pkg lifecycle_talker
오잉?
메세지가 나오지 않는다.
뭐가 잘 못 된 것일까?
일반 node와 lifecycle node가 다른 점은 node를 껐다 켰다 할 수 있다는 점이다.
그렇기 때문에 앞서 실습3에서 executable을 실행해줬지만 node 상태가 unconfigured라서 아무 메세지도 출력되지 않는 것이다.
lifecycle node를 만들 때 on_configure, on_active, on_deactive, on_cleanup, on_shutdown method를 구현해주면 이에 상응하는 service들을 이용할 수 있게 된다.
오늘은 두가지 서비스에 대해서 배워볼 예정이다.
rqt service caller가 익숙하지 않은 사람은 이 글 에서 5.rqt 실습을 참고 바란다.
다음과 같이 두개의 service caller를 열어준다. 두개의 service caller를 구성하려면 service caller를 구성하는 것을 단순히 2번 반복하면 된다.
(2개의 rqt service caller를 구성한 예시)
여기서는 다음과 같은 시나리오를 실습해보자
그 후, on_activate() 호출하기
(예시)
그 후, on_deactivate() 호출하기
(예시)
그 후, on_cleanup()호출하기
(예시)
마지막으로 unconfigured 상태일 때 on_shutdown() 호출하기
(예시)
해당 서비스는 이용하는 방법이 간단하다.
그냥 우측 상단에 call을 누르면 lifecycle node의 현재 상태를 알려준다.
위 실습 4.2를 진행하면서 다음과 같은 상태들을 확인해보자.
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using std::placeholders::_1;
#include "rclcpp_lifecycle/lifecycle_node.hpp"
class MinimalSubscriber : public rclcpp_lifecycle::LifecycleNode
{
public:
MinimalSubscriber()
: rclcpp_lifecycle::LifecycleNode("minimal_subscriber")
{
// subscription_ = this->create_subscription<std_msgs::msg::String>(
// "topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &state)
{
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
m_isActivated = false;
RCUTILS_LOG_INFO_NAMED(get_name(), "on_configure() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State &state)
{
m_isActivated = true;
RCUTILS_LOG_INFO_NAMED(get_name(), "on_activate() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State &state)
{
m_isActivated = false;
RCUTILS_LOG_INFO_NAMED(get_name(), "on_deactivate() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(const rclcpp_lifecycle::State &state)
{
subscription_.reset();
RCUTILS_LOG_INFO_NAMED(get_name(), "on cleanup is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(const rclcpp_lifecycle::State &state)
{
subscription_.reset();
RCUTILS_LOG_INFO_NAMED(get_name(), "on shutdown is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
private:
void topic_callback(const std_msgs::msg::String &msg) const
{
if (m_isActivated)
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
}
else
{
RCLCPP_INFO(
get_logger(), "Subscriber is currently inactive. Callback function is not working .");
}
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
bool m_isActivated = false;
// std::shared_ptr<rclcpp_lifecycle::LifecycleSusbcription<std_msgs::msg::String>> subscription_; -> unfortunately no such thing
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
std::shared_ptr<MinimalSubscriber> minimal_subscriber = std::make_shared<MinimalSubscriber>();
rclcpp::spin(minimal_subscriber->get_node_base_interface());
// rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
그럼 lifecycle 용 subscription이 없는데 어떻게 lifecycle node 처럼 동작시킬 수 있는지 위의 코드를 하나하나 분석해보자!
제일 먼저 살펴볼 부분은 필수 헤더파일을 추가하는 것이다.
다음 과정은 node를 만들려면 class가 필요하기 때문에 class 생성자(constructor)를 정의해준다!
lifecycle node의 구색을 갖추기 위해서는 on_configure(), on_activate(), on_deactivate(), on_cleanup(), on_shutdown()이라는 함수가 필요했었다.
on_configure()부터 정의하자.
좋아 on_configure()를 정의했다. 이제 on_activate로 이동하자!
on_activate도 별거 아니였다. on_deactivate는 어떨까? 한 번 살펴보자.
lifecycle node 정의를 알고 있으니 on_deactivate도 너무 쉬웠다.
on_cleanup에서는 무엇을 해야할까?
그렇다. on_configure에서 생성해줬던 기능 수행시 필요한 변수, 객체등을 제거해줘야한다.
여기서는 subscription이 그 변수, 객체등에 해당한다.
이를 제거하기 위해 다음과 같이 코드를 작성할 수 있다.
거의 다왔다. 이제 on_shutdown()만 정의하면된다. shutdown은 무슨 역할을 했던가? 그렇다. node가 없어지기전 node에 있던 변수들의 메모리등을 안전하게 해제해주면된다.
그렇기 때문에 cleanup에서 하는 작업과 다소 겹치는 부분이 있다.
어떻게 하는지 코드로 살펴보자.
좋아! 이제 lifecycle node 기본 기능(안전하게 끄고, 켜기)을 위한 함수들을 모두 구현했다.
이제 실제 node가 수행해야하는 기능(listenr: 메세지를 듣고 적절한 행동을 취하는 것)을 위한 디테일들을 신경써보자.
먼저 topic message를 구독할 때 수행하고 싶은 동작을 정의해야한다.
이제 우리가 사용했던 멤버 변수들을 초기화해주는 과정을 살펴보자.
드이어 대망의 node 생성하는 부분이다.
실제로 node가 생성되고 동작하는 코드이므로 매우 중요한 부분이라고 볼 수 있다.
하나하나 설명하느라 길었지만 결국에는 lifecycle node에 subscription이 있을 때도 on_configure, on_activate, on_deactive, on_cleanup, on_shutdown이 lifecyce node의 현재 상태를 어떤 상태로 만들어야하는지만 기억하면 구현하는 것 자체는 간단하다!
source code를 작성했으니 이제 CMakeLists.txt와 package.xml을 수정해주자.
다음 코드를 적절히 추가해준다.
full code는 github repository에 업로드해놨으니 참고하자!
add_executable(lifecycle_listener src/lifecycle_listener.cpp)
ament_target_dependencies(lifecycle_listener rclcpp std_msgs rclcpp_lifecycle)
install(TARGETS
lifecycle_talker
lifecycle_listener
#lifecycle_service_client
DESTINATION lib/${PROJECT_NAME})
-package.xml 같은 경우는 lifecycle_listener가 lifecycle_talker와 의존 패키지들(rclcpp, std_msgs, rclcpp_lifecycle)이 동일하므로 따로 추가할 것이 없다.
이제 build하면 된다.
다음 명령어들을 각각 실행해주자.
cd ~/simple_lifecycle_ws
colcon build
빌드가 완료되면 실행하자.
cd ~/simple_lifecycle_ws
source install/setup.bash
ros2 run simple_lifecycle_pkg lifecycle_listener
아마 아무 메세지도 출력되지 않을 것이다.
당연하다. rqt를 열어서 lifecycle_talker 실습에서 처럼 service call을 해보자.
이는 실습 5.3의 개인 연습으로 남겨두도록 하겠다.
힌트: change_state 서비스를 호출 할 때 현재 lifecycle node상태와 호출하려는 상태의 순서를 주의하자.
잘 모르겠을 시 lifecycle node state machine 그림을 참고하면서 천천히 해보자.
rqt의 service caller를 통해 lifecycle node를 껐다 켰다 했는데, 이는 service client code를 통해서도 같은 동작이 가능하다는 의미이다.
service client code에 대해 개념이 가물가물 한 사람들은 예전 내용을 가볍게 읽어보도록 하자.
먼저 src 폴더에 "lifecycle_service_client.cpp" 라는 파일을 만들자.
일단 다음의 코드를 복사 붙여넣자. 해당 코드는 여기 에서 발췌 및 수정했음을 참고하자.
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "lifecycle_msgs/srv/change_state.hpp"
#include "lifecycle_msgs/srv/get_state.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"
using namespace std::chrono_literals;
// which node to handle
static constexpr char const *lifecycle_node = "lc_talker";
// Every lifecycle node has various services
// attached to it. By convention, we use the format of
// <node name>/<service name>.
// In this demo, we use get_state and change_state
// and thus the two service topics are:
// lc_talker/get_state
// lc_talker/change_state
static constexpr char const *node_get_state_topic = "minimal_publisher/get_state";
static constexpr char const *node_change_state_topic = "minimal_publisher/change_state";
template <typename FutureT, typename WaitTimeT>
std::future_status
wait_for_result(
FutureT &future,
WaitTimeT time_to_wait)
{
auto end = std::chrono::steady_clock::now() + time_to_wait;
std::chrono::milliseconds wait_period(100);
std::future_status status = std::future_status::timeout;
do
{
auto now = std::chrono::steady_clock::now();
auto time_left = end - now;
if (time_left <= std::chrono::seconds(0))
{
break;
}
status = future.wait_for((time_left < wait_period) ? time_left : wait_period);
} while (rclcpp::ok() && status != std::future_status::ready);
return status;
}
class LifecycleServiceClient : public rclcpp::Node
{
public:
explicit LifecycleServiceClient(const std::string &node_name)
: Node(node_name)
{
}
void
init()
{
// Every lifecycle node spawns automatically a couple
// of services which allow an external interaction with
// these nodes.
// The two main important ones are GetState and ChangeState.
client_get_state_ = this->create_client<lifecycle_msgs::srv::GetState>(
node_get_state_topic);
client_change_state_ = this->create_client<lifecycle_msgs::srv::ChangeState>(
node_change_state_topic);
}
/// Requests the current state of the node
/**
* In this function, we send a service request
* asking for the current state of the node
* lc_talker.
* If it does return within the given time_out,
* we return the current state of the node, if
* not, we return an unknown state.
* \param time_out Duration in seconds specifying
* how long we wait for a response before returning
* unknown state
*/
unsigned int
get_state(std::chrono::seconds time_out = 3s)
{
auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();
if (!client_get_state_->wait_for_service(time_out))
{
RCLCPP_ERROR(
get_logger(),
"Service %s is not available.",
client_get_state_->get_service_name());
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
// We send the service request for asking the current
// state of the lc_talker node.
auto future_result = client_get_state_->async_send_request(request).future.share();
// Let's wait until we have the answer from the node.
// If the request times out, we return an unknown state.
auto future_status = wait_for_result(future_result, time_out);
if (future_status != std::future_status::ready)
{
RCLCPP_ERROR(
get_logger(), "Server time out while getting current state for node %s", lifecycle_node);
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
// We have an succesful answer. So let's print the current state.
if (future_result.get())
{
RCLCPP_INFO(
get_logger(), "Node %s has current state %s.",
lifecycle_node, future_result.get()->current_state.label.c_str());
return future_result.get()->current_state.id;
}
else
{
RCLCPP_ERROR(
get_logger(), "Failed to get current state for node %s", lifecycle_node);
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
}
/// Invokes a transition
/**
* We send a Service request and indicate
* that we want to invoke transition with
* the id "transition".
* By default, these transitions are
* - configure
* - activate
* - cleanup
* - shutdown
* \param transition id specifying which
* transition to invoke
* \param time_out Duration in seconds specifying
* how long we wait for a response before returning
* unknown state
*/
bool
change_state(std::uint8_t transition, std::chrono::seconds time_out = 3s)
{
auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();
request->transition.id = transition;
if (!client_change_state_->wait_for_service(time_out))
{
RCLCPP_ERROR(
get_logger(),
"Service %s is not available.",
client_change_state_->get_service_name());
return false;
}
// We send the request with the transition we want to invoke.
auto future_result = client_change_state_->async_send_request(request).future.share();
// Let's wait until we have the answer from the node.
// If the request times out, we return an unknown state.
auto future_status = wait_for_result(future_result, time_out);
if (future_status != std::future_status::ready)
{
RCLCPP_ERROR(
get_logger(), "Server time out while getting current state for node %s", lifecycle_node);
return false;
}
// We have an answer, let's print our success.
if (future_result.get()->success)
{
RCLCPP_INFO(
get_logger(), "Transition %d successfully triggered.", static_cast<int>(transition));
return true;
}
else
{
RCLCPP_WARN(
get_logger(), "Failed to trigger transition %u", static_cast<unsigned int>(transition));
return false;
}
}
private:
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetState>> client_get_state_;
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::ChangeState>> client_change_state_;
};
/**
* This is a little independent
* script which triggers the
* default lifecycle of a node.
* It starts with configure, activate,
* deactivate, activate, deactivate,
* cleanup and finally shutdown
*/
void callee_script(std::shared_ptr<LifecycleServiceClient> lc_client)
{
rclcpp::WallRate time_between_state_changes(0.1); // 10s
// configure
{
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
// activate
{
time_between_state_changes.sleep();
if (!rclcpp::ok())
{
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
// deactivate
{
time_between_state_changes.sleep();
if (!rclcpp::ok())
{
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
// activate it again
{
time_between_state_changes.sleep();
if (!rclcpp::ok())
{
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
// and deactivate it again
{
time_between_state_changes.sleep();
if (!rclcpp::ok())
{
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
// we cleanup
{
time_between_state_changes.sleep();
if (!rclcpp::ok())
{
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
// and finally shutdown
// Note: We have to be precise here on which shutdown transition id to call
// We are currently in the unconfigured state and thus have to call
// TRANSITION_UNCONFIGURED_SHUTDOWN
{
time_between_state_changes.sleep();
if (!rclcpp::ok())
{
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN))
{
return;
}
if (!lc_client->get_state())
{
return;
}
}
}
void wake_executor(std::shared_future<void> future, rclcpp::executors::SingleThreadedExecutor &exec)
{
future.wait();
// Wake the executor when the script is done
// https://github.com/ros2/rclcpp/issues/1916
exec.cancel();
}
int main(int argc, char **argv)
{
// force flush of the stdout buffer.
// this ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
auto lc_client = std::make_shared<LifecycleServiceClient>("lc_client");
lc_client->init();
rclcpp::executors::SingleThreadedExecutor exe;
exe.add_node(lc_client);
std::shared_future<void> script = std::async(
std::launch::async,
std::bind(callee_script, lc_client));
auto wake_exec = std::async(
std::launch::async,
std::bind(wake_executor, script, std::ref(exe)));
exe.spin_until_future_complete(script);
rclcpp::shutdown();
return 0;
}
뭐가 굉장히 길다..
포기할까? 당연히 아니다.
너무 겁먹을게 없는게 반복되는 작업이 많아서 그렇지 원리는 간단한다
이걸 code로 작성하기 위해 부가적인 코드들이 많이 추가됐을 뿐이다.
자 이제 그 무서워보이는 코드. 파헤쳐보자!!
역시 코드 작성 제일 처음에는 헤더파일들을 추가해줘야한다.
그래야 원하는 함수등을 쓸 수 있을테니 말이다.
service를 호출할 client는 node형태로 만들어진다.
이미 알다시피 node는 class 형태로 만들 수 있다.
이 node의 주요 기능은 lifecycle_talker의 service를 request하는 것이다. 따라서 client가 필요하므로 client들을 만들어주자.
먼저 client 변수들을 private으로 만들어준다.
이 client들은 이제 init()함수가 호출될 때 다음과 같이 생성된다.
그럼 이제 이 client 들을 사용하는 함수를 구현해보자.
lifecycle node의 상태를 바꾸고 나서 유효한 상태인지 체크하는 것이 디버깅할 때 유리하다.
그러면 node 상태를 획득할 수 있는 get_state함수를 살펴보자.
client_get_state를 사용해서 lifecycle node의 현재 상태를 획득할 것이다.
먼저 아래 코드를 살펴보자.
이어서 함수의 나머지 부분을 살펴보자.
이렇게 lifecycle의 node 상태를 획득하는 client 코드를 구현했다.
복잡한거 같지만 service server가 응답하지 않을 수 있는 상태를 여러 if문에 거쳐 확인하고 node 상태를 유효하게 획득한 경우에만 처리하는 것을 길게 써놓았을 뿐이다.
목적은 간단하다. node의 상태 획득하는거!
그렇다면 get_state 함수에서 사용된 wait_for_result는 어떻게 구현될까?
실제 숫자를 넣어 생각하면 수월하니 예시를 들어 살펴보자.
이러한 절차를 거쳐 service로 요청한 작업이 준비가 됐는지 안됐는지를 판단한다.
아직 많이 낯설다면 "아 이렇게 service 요청을 기다리는 코드를 짤 수 있구나" 하고 넘어가고 나중에 직접 짜야할 때 해당 코드를 참고하면된다. 걱정은 No!
앞서 node 상태 확인하는 함수를 구현했는데, 이제는 어떤 함수를 구현해야할까?
그렇다! 본격적으로 node의 상태를 바꾸는 함수가 필요하다.
이 코드에서는 change_state함수를 통해 해당 기능을 수행하고 있다.
어떻게 바꾸는지 하나하나 살펴보자.
복잡해보이지만 change_state 절차를 정리하자면 다음과 같다. 괄호 안에 있는 것은 실생활에 비유한 예시이니 참고하도록하자.
1. request 메세지를 만든다. (e.g. 먹고 싶은 음식 생각)
2. service가 준비되었는지 확인한다.(e.g. 식당 열렸는지 확인)
3. request를 보낸다. (e.g. 키오스크로 음식주문)
4. request가 시간내 처리됐는지 확인 (e.g. 음식이 너무 늦게 나오지 않는지 확인)
5. request가 제대로 처리됐는지 확인 (e.g. 내가 시킨 음식이 알맞게 나왔는지 확인)
코드는 긴거 같지만 논리는 별거아닌 것 같다. ㅎㅎ
LifecycleServiceClient class내에서 구현해야할 것은 다했다.
이제 뭐가 더 필요할까?
LifecycleServiceClient class내 멤버 method를 상태를 바꿀때마다 호출하면 되지만 이 과정을 좀 더 자동화할 순 없을까?
이를 callee_script라는 함수를 추가로 구현해서 처리할 수 있다.
lifecycle node 상태를 제어하는 시나리오는 무수히 많겠지만 이 함수에서는 다음과 같은 시나리오로 node 상태를 변화시킬 것이다.
자 그럼 어떻게 코드를 구성할 수 있는지 파헤쳐보자!
자 그럼 이제 본격적으로 callee_script를 호출할 main 함수를 작성해보자.
아직 안배운 executor가 등장하지만 겁먹지 말자!
자. 뭔가 호출하고 기다리는 과정이 많았다.
특히 async라는 표현과 future, wait 등 낯선 용어들이 있었는데 간단히 요약하면
전체적으로 다시 main 함수를 정리하자면
자 이렇게 대망의 lifecycle_service_client.cpp 분석이 끝났다. 기지개 쭉 펴고 빌드하기 위해 CMakeLists.txt와 package.xml을 수정하러 가자!
CMakeLists.txt에 다음과 같이 executable 이름과 dependencies를 추가한다. 해당 executable을 lifecycle_msgs에 의존성을 갖는다는 것을 상기하자. 전체 완성본은 github코드를 참고하기!
add_executable(lifecycle_service_client src/lifecycle_service_client.cpp)
ament_target_dependencies(lifecycle_service_client
"lifecycle_msgs"
"rclcpp_lifecycle"
)
추가로 lifecycle_service_client를 설치하는 코드를 다음과 같이 추가한다.
install(TARGETS
lifecycle_talker
lifecycle_listener
lifecycle_service_client
DESTINATION lib/${PROJECT_NAME})
<depend>lifecycle_msgs</depend>
변경사항들을 저장하고 새로운 터미널을 열어 빌드한다.
cd ~/simple_lifecycle_ws
colcon build
자 그럼 lifecycle_service_client를 실행해보자!
이때 lifecycle_talker를 먼저 실행해주는 것을 잊지말자.
cd ~/simple_lifecycle_ws
source install/setup.bash
ros2 run simple_lifecycle_pkg lifecycle_talker
cd ~/simple_lifecycle_ws
source install/setup.bash
ros2 run simple_lifecycle_pkg lifecycle_service_client
그러면 client가 lifecycle_talker의 상태를 변화시키면서 다음과 같은 메세지들이 각각의 터미널에서 출력될 것이다.
client 실행한 터미널
talker 실행한 터미널
자세히 살펴보면 inactive -> active -> inactive -> active -> inactive -> unconfigured -> finalized 가 된 것을 확인할 수 있다.
야호!
이번시간에는 이렇게 lifecycle node가 왜 필요하며 어떻게 구현할 수 있는지 알아봤다.
수많은 용어가 등장하긴 했지만 사실 본질은 사용하는 node는 켜주고 사용하지 않는 node는 꺼주고 이상이 있는 node는 어떤 상태에 있는지 등을 파악하기 위한 것으로 간단한다.
그러니 너무 어렵게 생각하지말자!
state machine을 보면서 오늘 배운 용어를 다시 머릿속으로 정리해보자.
lifecycle만드는 순서 요약
이렇게 정리하고 보니 흐름을 5줄로 요약이 가능하다.
별거 없네 하면서 자신감을 갖도록 하자.
다음시간엔 우리 로봇이 동시에 여러가지 일을 처리할 수 있도록 도와주는 executor와 callback group에 대해 다뤄보도록 하겠다. 많은 관심 바란다.
다음번 주제 executor & callback groups
관련 원문 링크:
개념
https://docs.ros.org/en/humble/Concepts/Intermediate/About-Executors.html#executors
예제
https://docs.ros.org/en/humble/How-To-Guides/Using-callback-groups.html#using-callback-groups
질문하고 싶거나 인공지능 & 로봇 개발에 대해 다뤄줬으면 하는 주제를 댓글로 남겨주기 바란다~!
문의메일: irobou0915@gmail.com
오웃 라이클사이클 내용이 기네요. 잘 볼게요!