ROS2 humble에서 기존에 존재하는 workspace 내부에
realsense2 를 빌드하겠습니다.
ROS2에서 realsense 용 별도 패키지를 설치하실 분은 아래 링크 과정을 따르시기 바랍니다.
저는 이미 UR 로봇을 빌드한 패키지가 있고,
이 위에서 Realsense D435를 작동시키려 하기 때문에 여러 과정들이 생략되어있습니다.
먼저 ros2 humble 용 realsense2 패키지를 설치합니다.
이전에 RealSense SDK가 설치되어 있어야 합니다.
export COLCON_WS=~/workspace/ros_ur_driver
cd $COLCON_WS
cd src
git clone https://github.com/IntelRealSense/realsense-ros.git -b ros2-development
cd ..
colcon build
source install/setup.bash
그리고 D435 camera 노드를 활성화 하겠습니다.
ros2 launch realsense2_camera rs_launch.py
그리고 새로운 터미널을 열고 로봇과 함께 rviz를 열어주겠습니다.
export COLCON_WS=~/workspace/ros_ur_driver
cd $COLCON_WS
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur3e robot_ip:=192.168.1.101 launch_rviz:=true
그럼 저희가 알던 화면이 나타나는데요,
이 상태에서 Add 를 선택하고 color frame 카메라 토픽을 추가해주면 추가가 될 뿐
화면이 나타나진 않습니다.
이 때 Global options에서 Fixed Frame을
camera_color_frame 으로 변경해주어야 카메라 화면이 나타납니다.
패키지를 같이 붙였는데도 왜 그럴까요?
한 번 확인해보겠습니다.
새 터미널을 열고 아래 명령어를 바로 칩니다.
ros2 run tf2_tools view_frames
그러면 home 디렉토리에 다음과 같은 frame ~~ .pdf 가 생겨납니다.
즉, 지금 저희가 다루는 로봇과 camera는 아예 다른 세상에 있다는 것을 확인할 수 있습니다.
저는 로봇과 카메라가 한 세상에 함께 있으면 좋겠습니다.
이를 위해선 urdf 파일을 수정해야하는데요,
일단 임시로 테스트를 위해서 카메라와 유사한 박스 하나를
UR3e인 마지막 링크 wrist_3_link 에 연결하겠습니다.
~/workspace/ros_ur_driver/src/Universal_Robots_ROS2_Description/urdf/ur.urdf.xacro
파일을 열고
아래와 같이 정의된 카메라 조인트를 wrist_3_link 와 같이 이동하도록 고정시켰습니다.
아래 코드는 해당 파일의 100번째 line 이후에 추가시켜주었습니다.
<!-- RealSense Camera Link -->
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.025 0.09 0.025"/>
</geometry>
<material name="black"/>
</visual>
</link>
<!-- Joint connecting last link and camera_link -->
<joint name="camera_joint" type="fixed">
<parent link="wrist_3_link"/>
<child link="camera_link"/>
<origin xyz="-0.055 0.0 0.0" rpy="0 4.71 0"/>
</joint>
그리고 위에서 했던 과정을 반복해보면,
실제로 카메라가 똑같은 world에 붙었다는 것을 확인할 수 있습니다.
이번에는 앞 과정에 더해 Add에서 /camera/depth 토픽을 선택하셔서
PointCloud2 를 실행해보시기 바랍니다.
카메라 노드를 아래 명령으로 다시 시작시켜야 합니다.
ros2 launch realsense2_camera rs_launch.py depth_module.profile:=1280x720x30 pointcloud.enable:=true
그럼 홈 위치에서 아래와 같은 결과가 나타날 것입니다.
아직 Depth Camera 를 UR에 장착시키지 않았기 때문에 제 모습이 나오지만,
실제로 URDF 를 통해 부착이 잘 이루어졌다는 것을 알 수 있습니다.
그럼 이제 지난 글에서 작성했던 Pick and Place cpp 코드를 초기 위치, 종료 위치만 다음과 같이 수정해서 3번째 터미널에서 moveit2, 4번째 터미널에서 pick and place launch 파일을 실행해보시기 바랍니다.
joint_group_positions_arm[0] = PI*10/18; // Shoulder Pan
joint_group_positions_arm[1] = -PI/2; // Shoulder Lift
joint_group_positions_arm[2] = PI/4; // Elbow
joint_group_positions_arm[3] = -PI/4; // Wrist 1
joint_group_positions_arm[4] = -PI/2; // Wrist 2
joint_group_positions_arm[5] = PI/2; // Wrist 3
실행하면 다음과 같은 결과가 나타납니다.
wrist_3_link 가 움직임에 따라 카메라와 해당 촬영 화면이 따라오는 모습을 확인할 수 있습니다.
그럼 다음번엔 카메라 urdf에 D435 mesh를 입히고, UR3e에 카메라를 실제로 장착시켜보겠습니다.
'Setup & Example > ROS2 + 예제' 카테고리의 다른 글
ROS2 MoveIt2 이용하여 UR3e 의 Link Position 및 Quaternion 획득하기 (0) | 2024.01.31 |
---|---|
ROS2 MoveIt2 에서 UR3e + Intel RealSense Pick and Place 예제 수행 (3) | 2024.01.27 |
ROS2 MoveIt2 이용하여 UR3e Pick and Place 수행하기 (0) | 2024.01.19 |
ROS2 humble에서 UR3e 작동 및 MoveIt2 Path Planning (1) | 2024.01.18 |
ROS2 humble에서 OpenManipulator-X Pick and Place + yolov8 으로 시작 명령 주기 (0) | 2024.01.05 |