프로젝트 마감 기한이 얼마남지 않았고, 공부와 프로젝트 결과물 제출이 병행하려고 하니 많은 어려움이 있는 것 같다.
ROS2와 임베디드 시스템에서 Micro ros 라이브러리를 사용하여 모빌리티 플랫폼을 만들려고 하였으나,
아진 배경지식이 부족해서 벽을 느꼈다...시간이 좀 더 있다면 해결할 수 있을 것 같은데
급한 불을 끄는게 먼저니 일단은 비교적 라이브러리도 많고 주변에서 도움을 많이 받을 수 있는 ROS를 사용하려고 한다.
이전에는 ROS 2와 아두이노 DUE에서 Topic 값을 보면서 모터를 구동시켰고, 이번 시간에는
아두이노 우노와 Docker 컨테이너에서 ROS noetic 그리고 통신은 Rosserial을 이용한다.
모터드라이버 사용방법이나 아두이노와 ROS 통신은 이전 포스트들과 매우 유사하니 참고하면 좋을 것 같다.
https://stupidly-honest.tistory.com/40
Setup
보드 : 아두이노 Uno
ROS Version : ROS noetic
motor Driver : Cytron MDD20A
DC Motor with Encoder : NEX-16002 DC Motor 12V 120RPM 64:1
참고자료
https://automaticaddison.com/how-to-publish-wheel-encoder-tick-data-using-ros-and-arduino/
1. Rosserial Setup
1. rosserial package install
$ sudo apt-get install ros-noetic-rosserial-arduino
$ sudo apt-get install ros-noetic-rosserial
2. rosserial lib install
먼저 rosserial 라이브러리를 설치하자.
고맙게도 아두이노 스케치에서 제공해준다. (필자의 아두이노 스케치 버전은 1.8.19)
library manager -> rosserial 검색 후, install
그 다음은 위 참고자료에서 가져온 코드를 실행 해보자
각자 모터와 아두이노에 연결한 핀을 수정할 필요가 있다.
(issue: rosserial 기본 예제는 작동을 안하지만 아래 코드는 정상작동한다.)
Code
/*
* Author: Automatic Addison
* Website: https://automaticaddison.com
* Description: ROS node that publishes the accumulated ticks for each wheel
* (right_ticks and left_ticks topics) using the built-in encoder
* (forward = positive; reverse = negative)
*/
#include <ros.h>
#include <std_msgs/Int16.h>
// Handles startup and shutdown of ROS
ros::NodeHandle nh;
// Encoder output to Arduino Interrupt pin. Tracks the tick count.
#define ENC_IN_LEFT_A 2
#define ENC_IN_LEFT_B 4
// Other encoder output to Arduino to keep track of wheel direction
// Tracks the direction of rotation.
#define ENC_IN_RIGHT_A 3
#define ENC_IN_RIGHT_B 11
// True = Forward; False = Reverse
boolean Direction_left = true;
boolean Direction_right = true;
// Minumum and maximum values for 16-bit integers
const int encoder_minimum = -32768;
const int encoder_maximum = 32767;
// Keep track of the number of wheel ticks
std_msgs::Int16 right_wheel_tick_count;
ros::Publisher rightPub("right_ticks", &right_wheel_tick_count);
std_msgs::Int16 left_wheel_tick_count;
ros::Publisher leftPub("left_ticks", &left_wheel_tick_count);
// 100ms interval for measurements
const int interval = 100;
long previousMillis = 0;
long currentMillis = 0;
// Increment the number of ticks
void right_wheel_tick() {
// Read the value for the encoder for the right wheel
int val = digitalRead(ENC_IN_RIGHT_B);
if(val == LOW) {
Direction_right = false; // Reverse
}
else {
Direction_right = true; // Forward
}
if (Direction_right) {
if (right_wheel_tick_count.data == encoder_maximum) {
right_wheel_tick_count.data = encoder_minimum;
}
else {
right_wheel_tick_count.data++;
}
}
else {
if (right_wheel_tick_count.data == encoder_minimum) {
right_wheel_tick_count.data = encoder_maximum;
}
else {
right_wheel_tick_count.data--;
}
}
}
// Increment the number of ticks
void left_wheel_tick() {
// Read the value for the encoder for the left wheel
int val = digitalRead(ENC_IN_LEFT_B);
if(val == LOW) {
Direction_left = true; // Reverse
}
else {
Direction_left = false; // Forward
}
if (Direction_left) {
if (left_wheel_tick_count.data == encoder_maximum) {
left_wheel_tick_count.data = encoder_minimum;
}
else {
left_wheel_tick_count.data--;
}
}
else {
if (left_wheel_tick_count.data == encoder_minimum) {
left_wheel_tick_count.data = encoder_maximum;
}
else {
left_wheel_tick_count.data++;
}
}
}
void setup() {
// Set pin states of the encoder
pinMode(ENC_IN_LEFT_A , INPUT_PULLUP);
pinMode(ENC_IN_LEFT_B , INPUT);
pinMode(ENC_IN_RIGHT_A , INPUT_PULLUP);
pinMode(ENC_IN_RIGHT_B , INPUT);
// Every time the pin goes high, this is a tick
attachInterrupt(digitalPinToInterrupt(ENC_IN_LEFT_A), left_wheel_tick, RISING);
attachInterrupt(digitalPinToInterrupt(ENC_IN_RIGHT_A), right_wheel_tick, RISING);
// ROS Setup
nh.getHardware()->setBaud(115200);
nh.initNode();
nh.advertise(rightPub);
nh.advertise(leftPub);
}
void loop() {
// Record the time
currentMillis = millis();
// If 100ms have passed, print the number of ticks
if (currentMillis - previousMillis > interval) {
previousMillis = currentMillis;
rightPub.publish( &right_wheel_tick_count );
leftPub.publish( &left_wheel_tick_count );
nh.spinOnce();
}
}
Compile and build
정상적으로 업로딩이 되면
터미널을 켜자
그다음에 실행할 명령어는 다음과 같다.
Result
그 다음은 손으로 모터 샤프트 분을 돌려보자
아래 사진과 같이 값이 잘 변하는 것을 알 수 있다.
아두이노에서 엔코더 tick 값을 읽어 rosserial로 값을 보내는 원리이다.
다음은 전원을 넣고, 모터드라이브에 내장된 Test 버튼을 통해 엔코더 값을 확인해보자
(자세한 내용은 아래 영상 참고)
감사합니다.
'Robotics 🤖 > Ubee' 카테고리의 다른 글
[Ubee] catkin_make에서 cakin build로 빌드 툴 변경하기(feat : em Error) (2) | 2023.11.24 |
---|---|
cmd_vel topic으로 로봇 액추에이터 구동하기 (0) | 2023.09.16 |
cmd_vel topic을 위한 파라미터 수정하기(ROS) (0) | 2023.09.16 |
아두이노 + ROS 2 튜토리얼 [2] (10) | 2023.08.29 |
아두이노 + ROS 2 튜토리얼 (12) | 2023.08.28 |