Main Content

rosbag

rosbag 로그 파일 열기 및 구문 분석

R2019b 이후

설명

예제

bag = rosbag(filename)은 경로 filename에 있는 rosbag의 모든 메시지 인덱스를 포함하고 있으면서 인덱싱 가능한 BagSelection 객체인 bag을 만듭니다. BagSelection 객체를 가져오려면 rosbag 함수를 사용합니다. 데이터에 액세스하려면 readMessages 함수 또는 timeseries 함수를 호출하여 관련 데이터를 추출합니다.

rosbag 또는 bag은 ROS 메시지 데이터를 저장하기 위한 파일 형식입니다. 주로 ROS 네트워크 내에서 메시지를 기록하는 데 사용됩니다. 또한 오프라인 분석, 시각화, 저장을 위해 bag을 사용할 수 있습니다. rosbag에 대한 자세한 내용은 ROS Wiki 페이지를 참조하십시오.

bagInfo = rosbag('info',filename)filename에 있는 rosbag의 내용에 대한 정보인 bagInfo를 구조체로 반환합니다.

예제

rosbag info filenamefilename에 있는 rosbag의 내용에 대한 정보를 MATLAB® 명령 창에 표시합니다. 이 정보에는 메시지 수, 시작 시간과 종료 시간, 토픽, 메시지 유형이 포함됩니다.

예제

모두 축소

rosbag에서 정보를 가져옵니다. MATLAB® 경로에 rosbag이 아직 없는 경우 rosbag에 대한 전체 경로를 지정합니다.

bagselect = rosbag('ex_multiple_topics.bag');

시간별, 토픽별로 필터링하여 메시지의 일부를 선택합니다.

bagselect2 = select(bagselect,'Time',...
    [bagselect.StartTime bagselect.StartTime + 1],'Topic','/odom');

rosbag 로그 파일에 대한 정보를 보기 위해 rosbag info filename을 사용합니다. 여기서 filename은 rosbag(.bag) 파일입니다.

rosbag info 'ex_multiple_topics.bag'
Path:     /tmp/Bdoc24a_2511836_3320146/tpd9b150c7/ros-ex32890909/ex_multiple_topics.bag
Version:  2.0
Duration: 2:00s (120s)
Start:    Dec 31 1969 19:03:21.34 (201.34)
End:      Dec 31 1969 19:05:21.34 (321.34)
Size:     23.6 MB
Messages: 36963
Types:    gazebo_msgs/LinkStates [48c080191eb15c41858319b4d8a609c2]
          nav_msgs/Odometry      [cd5e73d190d741a2f92e81eda573aca7]
          rosgraph_msgs/Clock    [a9c97c1d230cfc112e270351a944ee47]
          sensor_msgs/LaserScan  [90c7ef2dc6895d81024acba2ac42f369]
Topics:   /clock               12001 msgs  : rosgraph_msgs/Clock   
          /gazebo/link_states  11999 msgs  : gazebo_msgs/LinkStates
          /odom                11998 msgs  : nav_msgs/Odometry     
          /scan                  965 msgs  : sensor_msgs/LaserScan 

rosbag을 불러온 다음 사용할 수 있는 프레임을 확인하여 rosbag (.bag) 파일에서 변환을 가져옵니다. 이 프레임에서 getTransform 함수를 사용하여 두 좌표 프레임 간의 변환을 쿼리합니다.

rosbag을 불러옵니다.

bag = rosbag('ros_turtlesim.bag');

사용할 수 있는 프레임의 목록을 가져옵니다.

frames = bag.AvailableFrames;

두 좌표 프레임 간의 최근 변환을 가져옵니다.

tf = getTransform(bag,'world',frames{1});

특정 시간에 사용할 수 있는 변환을 확인하고 해당 변환을 가져옵니다. 사용할 수 있는 변환을 검사하기 위해 canTransform을 사용합니다. rostime 함수를 사용하여 시간을 지정합니다.

tfTime = rostime(bag.StartTime + 1);
if (canTransform(bag,'world',frames{1},tfTime))
    tf2 = getTransform(bag,'world',frames{1},tfTime);
end

rosbag을 불러옵니다.

bag = rosbag('ros_turtlesim.bag');

특정 토픽을 선택합니다.

bSel = select(bag,'Topic','/turtle1/pose');

메시지를 구조체로 읽습니다. 메시지를 읽을 때 DataFormat 이름-값 쌍을 지정합니다. 반환된 구조체의 셀형 배열에서 첫 번째 구조체를 검사합니다.

msgStructs = readMessages(bSel,'DataFormat','struct');
msgStructs{1}
ans = struct with fields:
        MessageType: 'turtlesim/Pose'
                  X: 5.5016
                  Y: 6.3965
              Theta: 4.5377
     LinearVelocity: 1
    AngularVelocity: 0

메시지에서 xy 점을 추출하고 로봇 궤적을 플로팅합니다.

구조체에서 모든 X 필드와 Y 필드를 추출하기 위해 cellfun을 사용합니다. 이 필드는 rosbag을 기록할 동안의 로봇의 xy 위치를 나타냅니다.

xPoints = cellfun(@(m) double(m.X),msgStructs);
yPoints = cellfun(@(m) double(m.Y),msgStructs);
plot(xPoints,yPoints)

Figure contains an axes object. The axes object contains an object of type line.

입력 인수

모두 축소

액세스하려는 rosbag 파일 이름과 경로로, string형 스칼라 또는 문자형 벡터로 지정됩니다. 이 경로는 상대 경로이거나 절대 경로일 수 있습니다.

출력 인수

모두 축소

rosbag 메시지 선택으로, BagSelection 객체 핸들로 반환됩니다.

rosbag의 내용에 대한 정보로, 구조체로 반환됩니다. 이 구조체는 rosbag 파일 및 그 내용과 관련된 필드를 포함합니다. 구조체로 반환된 rosbag의 샘플 출력은 다음과 같습니다.

Path:     \ros\data\ex_multiple_topics.bag
Version:  2.0
Duration: 2:00s (120s)
Start:    Dec 31 1969 19:03:21.34 (201.34)
End:      Dec 31 1969 19:05:21.34 (321.34)
Size:     23.6 MB
Messages: 36963
Types:    gazebo_msgs/LinkStates [48c080191eb15c41858319b4d8a609c2]
          nav_msgs/Odometry      [cd5e73d190d741a2f92e81eda573aca7]
          rosgraph_msgs/Clock    [a9c97c1d230cfc112e270351a944ee47]
          sensor_msgs/LaserScan  [90c7ef2dc6895d81024acba2ac42f369]
Topics:   /clock               12001 msgs  : rosgraph_msgs/Clock   
          /gazebo/link_states  11999 msgs  : gazebo_msgs/LinkStates
          /odom                11998 msgs  : nav_msgs/Odometry     
          /scan                  965 msgs  : sensor_msgs/LaserScan 

버전 내역

R2019b에 개발됨