안녕하세요.
터틀봇3 OpenCR에서 아두이노를 통해 업로드 하는 펌웨어를 변경해서 사용하려고 하는데 ROS2 Bringup을 시작하면 통신 오류가 발생하면서 Bringup이 중단되는 문제가 발생하고 있습니다.
문제를 구글링 해봤는데 기존 터틀봇 소스코드에서 통신관련 설정에 아두이노 코드가 추가되어서 통신상 문제가 발생하는 것 같습니다. 이 펌웨어를 사용하면서 터틀봇 bringup이 작동하게 만들고 싶습니다. 어느 부분을 살펴야 할 지 알려주시면 감사드리겠습니다.
혹시 기존 터틀봇코어 펌웨어를 사용하면서 OpenCR의 OLLO 핀이나 기존 GPIO 핀을 사용해서 센서값을 퍼블리싱 해보신 분들의 경험을 듣고 싶습니다.
사용환경
-
ubuntu 20.04
-
ros2 foxy
-
intel Nuc
-
변경된 OpenCR 아두이노 펌웨어
//터틀봇 코어 펌웨어
#include <Dynamixel2Arduino.h> // ROBOTIS 아두이노 다이나믹셀 패키지
#include <TurtleBot3_ROS2.h> // 터틀봇3 패키지
#include <SPI.h> // 시리얼통신 패키지
#include <MFRC522.h> // RFID 보드 패키지
#if defined(ARDUINO_OpenCR)
#define DXL_SERIAL Serial3
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 84;
#endif
#define RST_PIN 9
#define SS_PIN 14
MFRC522 rc522(SS_PIN, RST_PIN);
// 라인 센서 핀 정의 (아날로그 핀 사용)
int leftSensorPin = 42;
int rightSensorPin = 45;
// PID 상수
float kp = 1.0;
float ki = 0.0;
float kd = 0.3;
// PID 제어 변수
float error = 0;
float lastError = 0;
float integral = 0;
float derivative = 0;
float correction = 0;
// 최대 속도 제한 (300 RPM)
const float MAX_RPM = 300.0;
const float BASE_SPEED = 200.0; // 기본 모터 속도
const uint8_t DXL_ID_LEFT = 1; // 왼쪽 모터 ID
const uint8_t DXL_ID_RIGHT = 2; // 오른쪽 모터 ID
const float DXL_PROTOCOL_VERSION = 2.0;
extern Dynamixel2Arduino dxl;
using namespace ControlTableItem;
// 라인트레이싱 모드 플래그 (초기 상태는 비활성화)
bool lineTracingMode = false;
// 모드 전환 딜레이 시간 (밀리초)
unsigned long lastModeChangeTime = 0; // 마지막 모드 전환 시간 기록
const unsigned long modeChangeDelay = 5000; // 5초 딜레이
unsigned long previousMillis = 0; // 주기 제어를 위한 변수
void setup() {
DEBUG_SERIAL.begin(115200); // 시리얼 속도 조정
dxl.begin(1000000);
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
// 왼쪽 모터 초기화
dxl.ping(DXL_ID_LEFT);
dxl.torqueOff(DXL_ID_LEFT);
dxl.setOperatingMode(DXL_ID_LEFT, OP_VELOCITY);
dxl.torqueOn(DXL_ID_LEFT);
// 오른쪽 모터 초기화
dxl.ping(DXL_ID_RIGHT);
dxl.torqueOff(DXL_ID_RIGHT);
dxl.setOperatingMode(DXL_ID_RIGHT, OP_VELOCITY);
dxl.torqueOn(DXL_ID_RIGHT);
// TurtleBot3 초기화
TurtleBot3Core::begin(“Waffle”);
// RFID 모듈 초기화
SPI.begin();
rc522.PCD_Init();
}
void loop() {
unsigned long currentMillis = millis();
// TurtleBot3 코어는 항상 실행
TurtleBot3Core::run();
// RFID 카드 감지
if (rc522.PICC_IsNewCardPresent() && rc522.PICC_ReadCardSerial()) {
if (currentMillis - lastModeChangeTime >= modeChangeDelay) {
if (rc522.uid.uidByte[0] == 35 && rc522.uid.uidByte[1] == 178 &&
rc522.uid.uidByte[2] == 77 && rc522.uid.uidByte[3] == 14) {
lineTracingMode = !lineTracingMode; // RFID로 라인트레이싱 모드를 전환
lastModeChangeTime = currentMillis;
}
}
}
// 라인트레이싱 모드가 활성화된 경우에만 센서 데이터를 읽고 모터를 제어
if (lineTracingMode) {
// 라인 센서 값 읽기
int leftSensorValue = analogRead(leftSensorPin);
int rightSensorValue = analogRead(rightSensorPin);
// PID 제어 계산
error = leftSensorValue - rightSensorValue;
integral += error;
derivative = error - lastError;
correction = kp * error + ki * integral + kd * derivative;
// 모터 속도 계산
float leftMotorSpeed = BASE_SPEED - correction;
float rightMotorSpeed = BASE_SPEED + correction;
// 최대 속도 제한 적용
leftMotorSpeed = constrain(leftMotorSpeed, -MAX_RPM, MAX_RPM);
rightMotorSpeed = constrain(rightMotorSpeed, -MAX_RPM, MAX_RPM);
// 모터 속도 설정
dxl.setGoalVelocity(DXL_ID_LEFT, leftMotorSpeed);
dxl.setGoalVelocity(DXL_ID_RIGHT, rightMotorSpeed);
// 이전 오차 저장
lastError = error;
}
delay(10); // 짧은 대기 시간으로 루프가 너무 빨리 돌지 않도록 함
}
- Bringup 실행시 터미널 에러 문구
[INFO] [launch]: Default logging verbosity is set to INFO
urdf_file_name : turtlebot3_waffle_pi.urdf
[INFO] [robot_state_publisher-1]: process started with pid [73813]
[INFO] [ld08_driver-2]: process started with pid [73815]
[INFO] [turtlebot3_ros-3]: process started with pid [73817]
[robot_state_publisher-1] Parsing robot urdf xml string.
[robot_state_publisher-1] Link base_link had 7 children
[robot_state_publisher-1] Link camera_link had 1 children
[robot_state_publisher-1] Link camera_rgb_frame had 1 children
[robot_state_publisher-1] Link camera_rgb_optical_frame had 0 children
[robot_state_publisher-1] Link caster_back_left_link had 0 children
[robot_state_publisher-1] Link caster_back_right_link had 0 children
[robot_state_publisher-1] Link imu_link had 0 children
[robot_state_publisher-1] Link base_scan had 0 children
[robot_state_publisher-1] Link wheel_left_link had 0 children
[robot_state_publisher-1] Link wheel_right_link had 0 children
[robot_state_publisher-1] [INFO] [1729143891.441247483] [robot_state_publisher]: got segment base_footprint
[robot_state_publisher-1] [INFO] [1729143891.441435583] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1729143891.441458799] [robot_state_publisher]: got segment base_scan
[robot_state_publisher-1] [INFO] [1729143891.441470240] [robot_state_publisher]: got segment camera_link
[robot_state_publisher-1] [INFO] [1729143891.441482048] [robot_state_publisher]: got segment camera_rgb_frame
[robot_state_publisher-1] [INFO] [1729143891.441494028] [robot_state_publisher]: got segment camera_rgb_optical_frame
[robot_state_publisher-1] [INFO] [1729143891.441506794] [robot_state_publisher]: got segment caster_back_left_link
[robot_state_publisher-1] [INFO] [1729143891.441518692] [robot_state_publisher]: got segment caster_back_right_link
[robot_state_publisher-1] [INFO] [1729143891.441528992] [robot_state_publisher]: got segment imu_link
[robot_state_publisher-1] [INFO] [1729143891.441539586] [robot_state_publisher]: got segment wheel_left_link
[robot_state_publisher-1] [INFO] [1729143891.441550263] [robot_state_publisher]: got segment wheel_right_link
[turtlebot3_ros-3] [INFO] [1729143891.447977497] [turtlebot3_node]: Init TurtleBot3 Node Main
[turtlebot3_ros-3] [INFO] [1729143891.448249244] [turtlebot3_node]: Init DynamixelSDKWrapper
[turtlebot3_ros-3] [ERROR] [1729143891.448317059] [DynamixelSDKWrapper]: Failed to open the port(/dev/ttyACM0)!
[turtlebot3_ros-3] [ERROR] [1729143891.448326874] [DynamixelSDKWrapper]: Failed to initialize SDK handlers
[turtlebot3_ros-3] [ERROR] [1729143891.448346299] [turtlebot3_node]: Failed connection with Devices
[turtlebot3_ros-3] [PortHandlerLinux::SetupPort] Error opening serial port!
[turtlebot3_ros-3] [INFO] [1729143891.449449942] [turtlebot3_node]: Add Motors
[turtlebot3_ros-3] [INFO] [1729143891.449552597] [turtlebot3_node]: Add Wheels
[turtlebot3_ros-3] [INFO] [1729143891.449596817] [turtlebot3_node]: Add Sensors
[turtlebot3_ros-3] terminate called after throwing an instance of ‘rclcpp::exceptions::RCLError’
[turtlebot3_ros-3] what(): could not create publisher: rcl node’s context is invalid, at /tmp/binarydeb/ros-foxy-rcl-1.1.14/src/rcl/node.c:441
[ld08_driver-2] /dev/ttyACM0 OpenCR Virtual ComPort in FS Mode
[ld08_driver-2] /dev/ttyUSB0 CP2102 USB to UART Bridge Controller
[ld08_driver-2] FOUND LDS-02
[ld08_driver-2] LDS-02 started successfully
[ERROR] [turtlebot3_ros-3]: process has died [pid 73817, exit code -6, cmd ‘/home/kmkm/turtlebot3_ws/install/turtlebot3_node/lib/turtlebot3_node/turtlebot3_ros -i /dev/ttyACM0 --ros-args --params-file /home/kmkm/turtlebot3_ws/install/turtlebot3_bringup/share/turtlebot3_bringup/param/waffle_pi.yaml’].