ROS2의 action server와 action client를 이용해서
실제 turtlebot3 로봇과 가상 시뮬레이션 gazebo에서 구현
ROS2의 Action Server / Client를 이용해서 maze_action_server/client 노드를 실행하여
로봇이 미로를 탈출하는 패키지 프로젝트 입니다
Maze Action 프로젝트는
로봇은 turtlebot3 burger를 사용해서 실제 미로와 비슷하게 환경을 만들어서 수행하였습니다.
[미로를 책으로 설정, 로봇 turtlebot3]
(turtlebot3를 직접 사용하는 경우에 라즈베리파이에 설치합니다.)
maze_cation
├── maze
│ ├── CMakeLists.txt
│ ├── launch
│ │ └── maze_server.launch.py
│ ├── package.xml
│ └── src
│ ├── maze_client.cpp
│ └── maze_server.cpp
├── maze_dolly
│ ├── CMakeLists.txt
│ ├── launch
│ │ └── maze_dolly.launch.py
│ ├── models
│ │ ├── customized_dolly
│ │ └── wall_maze
│ └── worlds
│ └── maze_dolly.world
└── maze_interfaces
├── action
│ └── Maze.action
├── CMakeLists.txt
└── package.xml
Items | Model |
---|---|
IMU | Gyroscope 3 Axis, Accelerometer 3 Axis |
MCU | 32-bit ARM Cortex®-M7 with FPU |
SBC | Raspberry Pi 4b |
LDS | 360 Laser Distance Sensor LDS-02 |
Actuator | XL430-W250 |
ROS2 ; Foxy Fitzroy
Gazebo : ROS의 시뮬레이션 프로그램으로 실제 로봇없이 가상에서 시뮬레이션으로 구동이 가능
시뮬레이션으로 진행 할 시 gazebo 및 런치파일 실행
시뮬레이션으로 gazebo에서 실행할려고 할 때에는 maze_dolly 패키지의 런치파일로
실행합니다.
깃허브에서 클론해서 설치를 합니다.
Git hub 및 README를 확인해주세요
설치 방법 및 코드를 깃허브에서 확인할 수 있습니다.
코드는 c++로 작성하였습니다.
void execute(const std::shared_ptr<GoalHandleMaze> goal_handle) {
rclcpp::WallRate loop_rate(5);
const auto goal = goal_handle->get_goal(); //
auto feedback = std::make_shared<maze_interfaces::action::Maze::Feedback>();
auto result = std::make_shared<maze_interfaces::action::Maze::Result>();
// client로 부터 받은 goal에서 turning_sequence 만큼 반복
for (int val : goal->turning_sequence) {
RCLCPP_INFO(this->get_logger(), "Current Input: %d", val);
RCLCPP_INFO(this->get_logger(), "Turning %s ", direction_str_vec[val].c_str());
// 사용자에게 보여주기 위한 vector 스트링, 일치하는 문자열 프린트
feedback->feedback_msg = "Now.. turning " + direction_str_vec[val]; //client쪽에서 사용
RCLCPP_INFO(this->get_logger(), feedback->feedback_msg);
// 사용자 입력과(turning_sequence), direction_flt_vec(벡터: 방향값 수치)와 같은 배열의 value값을 turn_robot 메소드를 호출
turn_robot(direction_flt_vec[val]);
// feedback 보냄
goal_handle->publish_feedback(feedback);
// cmd_vel로 제어하는 메소드 호출
moving_robot();
}
// 이미지 처리를 위해서
auto image_subscriber = std::make_shared<ImageSubscriber>();
// ...
// 생략
// ...
// image_subscriber에서 처리한 result 값 결정해서 보내주기
if (!is_green) {
RCLCPP_ERROR(get_logger(), "====== Failed ======");
result->success = false;
goal_handle->abort(result);
} else {
RCLCPP_INFO(get_logger(), "====== Succeed ======");
result->success = true;
goal_handle->succeed(result);
}
}
void send_goal() {
using namespace std::placeholders;
auto goal_msg = maze_interfaces::action::Maze::Goal();
// 유저에게 입력받은 배열을 받아와서 action msg에 넣어주기
goal_msg.turning_sequence = this->get_turning_list();
auto send_goal_options = rclcpp_action::Client<maze_interfaces::action::Maze>::SendGoalOptions();
send_goal_options.goal_response_callback = std::bind(&MazeActionClient::goal_response_callback, this, _1);
send_goal_options.feedback_callback = std::bind(&MazeActionClient::feedback_callback, this, _1, _2);
send_goal_options.result_callback = std::bind(&MazeActionClient::result_callback, this, _1);
// async_send_goal()
auto goal_handle_future = this->action_client->async_send_goal(goal_msg, send_goal_options);
}
void feedback_callback(rclcpp_action::ClientGoalHandle<maze_interfaces::action::Maze>::SharedPtr,
const std::shared_ptr<const maze_interfaces::action::Maze::Feedback> feedback) {
// 서버에서 처리된 feedback을 출력
RCLCPP_INFO(this->get_logger(), "Received feedback: %s", feedback->feedback_msg.c_str());
}
void result_callback(const rclcpp_action::ClientGoalHandle<maze_interfaces::action::Maze>::WrappedResult & result) {
// 최종 result 여부
this->goal_done_ = true;
// ...
// 생략
// ...
// 최종적 결과로 비교
if (result.result->success != false) {
RCLCPP_WARN(this->get_logger(), "Congrats! Actions have been accompished!!");
}
}
cd ~/colcon_ws
. install/setup.sh
ros2 run maze maze_action_server_node
OR
ros2 launch maze_dolly maze_dolly.launch.py
새로 다른 터미널을 열어준 후에 maze_action_server를 실행시키기 위해 런치 파일 실행
ros2 launch maze maze_server.launch.py
source install/setup.sh
이번에는 maze_action_client 노드 실행함
ros2 run maze maze_action_client_node
노드 실행한 모습
/cmd_vel
/odom
/parameter_events
/rosout
/scan
/dolly/cmd_vel
/dolly/laser_scan
/dolly/odom
/parameter_events
/rosout
rqt_image_view 노드 실행으로 보기. 아래의 노드를 실행
ros2 run rqt_image_view rqt_image_view
이미지가 안 나오면 topic 부분을 다시 선택해준다 (또는 토픽 옆 새로고침 아이콘)
/camera0/image_raw
로봇을 미로에서 빠져나올 수 있게 녹색 공이 있는 출구를 향해서 방향을 입력합니다.
[방향 및 숫자 안내]turtlebot3 미로 탈출 성공 영상
turtlebot3 미로 탈출 실패 영상
Gazebo를 이용한 maze_dolly 패키지의 성공 영상
Gazebo를 이용한 maze_dolly 패키지의 실패 영상