728x90
- 1/10에 해당 문제 해결 (아랫 부분에 설명)
- 현재 자율주행 로봇의 메인 제어기로는 Jetson Xavier, 모터로 MDH100, 모터 드라이버로는 MD200T 사용중
- Ubuntu 20.04, ROS Noetic 환경에서 MDROBOT사에서 제공하는 모터 드라이버의 ROS 패키지를 통해 인휠모터를 제어하고자 함
https://www.mdrobot.co.kr/inwheelmotor-store/?idx=274
https://www.mdrobot.co.kr/BLDCMotordriverDCstore/?idx=160
https://github.com/YoungSeong98/md
- 아래의 USB to RS485 컨버터를 통해 모터 드라이버와 제어기를 연결
- Desktop 환경에서는 모터 드라이버를 통한 모터 제어가 제대로 되나, 임베디드 환경에서는 제대로 되지 않는 문제 발생
1) Desktop 환경에서의 모터 드라이버를 통한 모터 제어
$ cd ~/catkin_ws/src
$ git clone -b noetic-devel https://github.com/ROBOTIS-GIT/turtlebot3_msgs.git
$ git clone -b noetic-devel https://github.com/ROBOTIS-GIT/turtlebot3.git
$ cd ..
$ catkin_make
$ echo "export TURTLEBOT3_MODEL=waffle_pi">> ~/.bashrc
- catkin workspace에 모터 드라이버 ROS 패키지를 가져오고 구동 테스트를 위한 turtlebot3 관련 패키지 설치
- turtlebot3 패키지 구동을 위한 model 설정
$ sudo apt install ros-noetic-serial
- ros noetic serial 패키지 설치
- USB to RS485 컨버터를 통해 모터 드라이버와 노트북 연결
$ cd ~/catkin_ws
$ source devel/setup.bash
$ roslaunch md md_robot_node.launch
- 모터 드라이버 launch file 실행
$ cd ~/catkin_ws
$ source devel/setup.bash
$ roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch
- 모터 구동 테스트를 위해 teleop 실행
$ rostopic echo /cmd_vel
- teleop를 통해 모터가 정상 동작함을 확인하였으며 cmd_vel topic 또한 제대로 발행됨을 확인
2) Embedded Board 환경에서의 모터 드라이버를 통한 모터 제어
- Jetson Xavier/Nano, Raspberry Pi 총 3가지의 embedded board를 통해 모터 제어를 진행
- Jetson Board는 sdkmanager, Raspberry Pi는 Raspberry Pi Imager를 통해 Ubuntu 20.04 설치
- Desktop 환경과 동일하게 catkin workspace에 모터 드라이버 ROS 패키지와 turtlebot3 관련 패키지를 가져오고 ros noetic serial 패키지 설치
$ roslaunch md md_robot_node.launch
$ roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch
- USB to RS485 컨버터를 통해 모터 드라이버와 embedded board 연결 후 모터 드라이버 패키지와 teleop 실행
- 위처럼 teleop를 통한 cmd_vel 토픽은 제대로 발행이 되나 모터 제어가 제대로 되지 않음
- teleop창에서 키 입력을 통해 명령을 줄 시 모터가 제어가 되었다 되지 않았다를 반복함
- 아래 영상처럼 Desktop 환경에선 teleop창에서 명령을 줄 때마다 Data의 Transmit, Receive가 정상적으로 이뤄지나 Embedded 환경에선 's'를 제외한 모든 명령 입력시 Data의 Receive가 제대로 이뤄지지 않음
- 통신이 제대로 되지 않음이 원인이라고 추측하여 Low Latency를 변경
$ cd /sys/bus/usb-serial/devices/ttyUSB0
$ gedit latency_timer
- Jetson Xavier/Nano에서 위 directory로 이동하여 기본적으로 16으로 되어있는 low latency를 1로 변경
- 그리고 다시 모터 제어를 진행하였으나 여전히 제대로 제어가 되지 않음
- + subscriber/publisher node의 buffer size를 변화시켜봤으나 해결되지 않음
- Jetson Nano에서 아래와 같은 RS485 확장 보드를 통해 모터드라이버와 연결 후 위 과정을 진행하였으나 동일한 문제점 발생
- 현재 Jetson Xavier/Nano, Raspberry Pi 모든 Embedded Board에서 위와 같은 문제가 발생함 : ARM Core 구조로 인한 문제일 수도 있다고 추측됨
- 1/10 위 문제점 해결
- RMID(Receiving Machine ID) : 패킷의 첫번째 인식바이트(183, 모터제어기)
- TMID(Transmitting Machine ID) : 패킷의 두번째 인식바이트(TMID, 사용자 제어기)
- ID: 각제어기의 ID(0~253, Broadcasting ID: 254)
- PID : Parameter IDentification number
- CHK : Check Sum
- 사용자가 제어기로 보내는 경우의 헤더는 183, TMID, 받는 경우는 TMID, 183 이 됨
- Desktop 환경과 Embedded 환경에서의 통신 data를 비교해보니 Desktop 환경에서는 위 통신 packet이 제대로 전달되나 Embedded 환경에서는 CHK가 제대로 전달되지 않음
$ cd ~/catkin_ws/src/MD/src/md_robot_node/com.cpp
- md package의 com.cpp source code 분석
// com.cpp 파일 중 일부
uint8_t CalCheckSum(uint8_t *pData, uint16_t length)
{
uint8_t sum;
sum = 0;
for(int i = 0; i < length; i++) {
sum += *pData++;
}
sum = ~sum + 1; //check sum
return sum;
}
int PutMdData(PID_CMD_t pid, uint16_t rmid, const uint8_t *pData, uint16_t length)
{
uint8_t *p;
uint16_t len;
len = 0;›
serial_comm_snd_buff[len++] = rmid;
serial_comm_snd_buff[len++] = robotParamData.nIDPC;
serial_comm_snd_buff[len++] = 1;
serial_comm_snd_buff[len++] = (uint8_t)pid;
serial_comm_snd_buff[len++] = length;
p = (uint8_t *)&serial_comm_snd_buff[len];
memcpy((char *)p, (char *)pData, length);
len += length;
serial_comm_snd_buff[len++] = CalCheckSum(serial_comm_snd_buff, len);
{
if(fgInitsetting == INIT_SETTING_STATE_NONE) {
for(int i = 0; i < len; i++) {
ROS_INFO("%2d: 0x%02x, %3d", i, serial_comm_snd_buff[i], serial_comm_snd_buff[i]);
}
}
}
if(ser.isOpen() == true) {
ser.write(serial_comm_snd_buff, len);
}
return 1;
}
- Embedded 환경에서의 CHK값을 다시 확인하여 보니 255가 계속 뜸
- uint8_t가 표현 가능한 최대값이 255여서 통신 data가 overflow 되었을 수도 있다고 생각해 CalCheckSum의 return type과 sum의 data type을 모두 uint16_t로 변경
uint16_t CalCheckSum(uint8_t *pData, uint16_t length)
{
uint16_t sum;
sum = 0;
for(int i = 0; i < length; i++) {
sum += *pData++;
}
sum = ~sum + 1; //check sum
return sum;
}
- Embedded 환경에서 MD package를 build 한 후 다시 md_robot_node.launch와 turtlebot3_teleop_key.launch를 실행시켜 모터 제어
- 모터가 이제 제대로 동작함
- 결국 Embedded 환경에서는 parity bit 역할을 하는 CHK가 제대로 전달되지 않아 제어가 제대로 되지 않았다고 추측됨
- 의문점 : stdint.h에 정의되어있는 uint8_t는 모든 platform에서 동일한 bit수를 사용하게 하는데 왜 PC에서는 uint8_t를 써도 overflow가 발생하지 않는가?
- git clone을 통해 md package를 사용할 수 있도록 내 github에 md repository를 생성하고 해당 repository에 md package를 commit
https://github.com/YoungSeong98/md
'Project > RIS' 카테고리의 다른 글
[RIS] 1/9 (initial pose/goal, odometry publisher, ekf) (0) | 2023.01.09 |
---|---|
[RIS] 1/5 (__attribute, stdint.h, ros::Timer) (0) | 2023.01.06 |
[RIS] 1/2 (USB 장치의 Symbolic Link 생성법) (0) | 2023.01.02 |
[RIS] 12/26 (MDAS) (0) | 2022.12.26 |
[RIS] 12/5 (RealSense, TF) (0) | 2022.12.05 |