Skip to main content

비전 노드 연동

plem 플랫폼은 plem_msgs/action/VisionInspection 표준 인터페이스를 정의한다. 어떤 비전 백엔드(ZED depth, YOLO, classical CV, 바코드 리더 등)를 사용하든, 이 인터페이스를 구현하면 Teaching Pendant 및 사용자 애플리케이션에서 즉시 사용할 수 있다.

tip

Teaching Pendant는 이 인터페이스의 클라이언트 중 하나일 뿐이다. 사용자의 Python/C++ 코드에서도 동일한 action을 직접 호출할 수 있다.

표준 인터페이스

ros2 interface show plem_msgs/action/VisionInspection

Goal (요청)

필드타입설명
camera_idstring카메라 식별자 (launch 파라미터와 일치)
inspection_idstring검사 프로파일 이름 (사용자 정의)

Result (결과)

필드타입설명
detectedbool물체 감지 여부
confidencefloat64감지 신뢰도 [0.0 - 1.0]
object_posesgeometry_msgs/Pose[]감지된 물체 위치 (빈 배열 가능)
result_jsonstring확장 데이터 (JSON 문자열, 선택)

Feedback (진행 상태)

필드타입설명
stagestring"capturing", "processing", "complete"
progressfloat64진행률 [0.0 - 1.0]

최소 구현 예제 (Python)

import json
import rclpy
from rclpy.node import Node
from rclpy.action import ActionServer
from plem_msgs.action import VisionInspection
from geometry_msgs.msg import Pose

class VisionServer(Node):
def __init__(self):
super().__init__('vision_server')
robot_id = self.declare_parameter('robot_id', 'indy0').value
self._action_server = ActionServer(
self,
VisionInspection,
f'/{robot_id}/plem/vision_inspect',
self.execute_callback,
)
self.get_logger().info(f'Vision server ready at /{robot_id}/plem/vision_inspect')

async def execute_callback(self, goal_handle):
camera_id = goal_handle.request.camera_id
inspection_id = goal_handle.request.inspection_id
self.get_logger().info(f'Inspecting: camera={camera_id}, profile={inspection_id}')

# --- Feedback: capturing ---
feedback = VisionInspection.Feedback()
feedback.stage = 'capturing'
feedback.progress = 0.3
goal_handle.publish_feedback(feedback)

# === 여기에 비전 처리 로직 구현 ===
# 예: ZED depth, YOLO 추론, 바코드 스캔 등
detected = True
confidence = 0.95
pose = Pose()
pose.position.x = 0.3
pose.position.y = 0.1
pose.position.z = 0.05

# --- Feedback: processing ---
feedback.stage = 'processing'
feedback.progress = 0.7
goal_handle.publish_feedback(feedback)

# --- Result ---
result = VisionInspection.Result()
result.detected = detected
result.confidence = confidence
result.object_poses = [pose] if detected else []
result.result_json = json.dumps({'class': 'bolt', 'defects': []})

goal_handle.succeed()
return result

def main():
rclpy.init()
node = VisionServer()
rclpy.spin(node)

if __name__ == '__main__':
main()

네임스페이스 규칙

모든 plem 인터페이스는 /{robot_id}/plem/ 네임스페이스 아래에 위치한다:

/{robot_id}/plem/vision_inspect    # 비전 검사
/{robot_id}/plem/plan_trajectory # 궤적 계획
/{robot_id}/plem/set_mode # 모드 전환

Launch 파일에서 robot_id 파라미터를 전달한다:

Node(
package='my_vision_package',
executable='vision_server',
parameters=[{'robot_id': LaunchConfiguration('robot_id')}],
)

ZED 카메라 TF 정합

info

이 프레임은 2-Layer Description 패턴의 Description layer(stereolabs_description)에서 생성된다.

ZED 카메라를 비전 소스로 사용할 때, plem URDF가 생성하는 TF 프레임명과 ZED 드라이버가 publish하는 frame_id가 일치해야 한다.

plem은 공식 zed-ros2-wrapper의 URDF 매크로를 벤더링하므로, 프레임명이 자동으로 일치한다:

plem URDF 프레임ZED 드라이버 frame_id용도
{cam_name}_camera_link{camera_name}_camera_link마운트 기준
{cam_name}_left_camera_frame_optical{camera_name}_left_camera_frame_opticaldepth, point cloud

cam_namecamera_name이 동일한 값이면 (기본: cam) 프레임이 정확히 매칭된다.

tip

비전 서버에서 object_poses를 반환할 때, ZED 카메라의 optical frame({cam_name}_left_camera_frame_optical)을 기준으로 좌표를 제공하면 TF를 통해 base_link 기준으로 자동 변환할 수 있다.

caution

plem이 robot_state_publisher로 TF를 관리하므로, ZED 드라이버의 TF 발행을 반드시 비활성화해야 한다:

ros2 launch zed_wrapper zed_camera.launch.py \
camera_model:=zedxm camera_name:=cam \
--ros-args -r __ns:=/{robot_id} \
param_overrides:="pos_tracking.pos_tracking_enabled:=false;pos_tracking.publish_tf:=false;pos_tracking.publish_map_tf:=false;depth.depth_stabilization:=0"

두 소스가 동시에 TF를 발행하면 프레임 충돌이 발생하여 모든 좌표 변환이 실패한다.

CLI 테스트

비전 서버가 실행 중일 때:

# 액션 서버 확인
ros2 action list | grep vision

# Goal 전송
ros2 action send_goal /indy0/plem/vision_inspect plem_msgs/action/VisionInspection \
"{camera_id: 'cam_01', inspection_id: 'pick_check'}"

Teaching Pendant 연동

비전 서버가 실행 중이면 Teaching Pendant에서 자동으로 사용 가능하다:

  1. NodePicker → Skills → Vision Inspect 선택
  2. Camera ID, Inspection Profile 설정
  3. If / Else 노드에서 드롭다운으로 Object Detected? 선택
  4. 실행 (Play) → action 서버 호출 → 결과가 blackboard에 자동 저장

비전 서버가 실행 중이 아니면 action 호출이 타임아웃되어 FAILURE를 반환한다.

result_json 활용

표준 필드(detected, confidence, object_poses)로 부족한 경우, result_json에 JSON 문자열로 추가 데이터를 전달한다:

result.result_json = json.dumps({
'class': 'M5_bolt',
'defects': ['scratch', 'dent'],
'barcode': '4901234567890',
'processing_time_ms': 42,
})

현재 Teaching Pendant는 result_json을 blackboard에 문자열로 저장한다. 파싱은 향후 지원 예정.

여러 검사 프로파일

같은 카메라로 다른 검사를 수행하려면 inspection_id를 활용한다:

Flow 내 노드camera_idinspection_id
Vision Inspect (물체 감지)cam_01detect_bolt
Vision Inspect (품질 검사)cam_01quality_check
Vision Inspect (바코드)cam_01read_barcode

비전 서버에서 inspection_id에 따라 다른 처리 로직을 분기한다.