Main Content

send

토픽에 ROS 메시지 퍼블리시

R2019b 이후

설명

예제

send(pub,msg)는 publisher pub가 지정한 토픽에 메시지를 퍼블리시합니다. 이 메시지는 pub가 지정한 토픽을 서브스크라이브한 ROS 네트워크의 모든 subscriber가 수신할 수 있습니다.

예제

모두 축소

ROS 네트워크에서 메시지를 보내고 받을 publisher와 subscriber를 설정합니다.

ROS 네트워크에 연결합니다.

rosinit
Launching ROS Core...
Done in 0.77453 seconds.
Initializing ROS master on http://172.29.217.125:56013.
Initializing global node /matlab_global_node_49233 with NodeURI http://dcc934856glnxa64:42035/ and MasterURI http://localhost:56013.

특정 토픽과 메시지 유형을 가진 publisher를 만듭니다. 이 publisher를 사용하여 보낼 디폴트 메시지를 반환할 수도 있습니다.

[pub,msg] = rospublisher('position','geometry_msgs/Point');

네트워크를 통해 보내기 전에 메시지를 수정합니다.

msg.X = 1;
msg.Y = 2;
send(pub,msg);

subscriber를 만들고 최신 메시지를 기다립니다. 보낸 메시지가 맞는지 확인합니다.

sub = rossubscriber('position')
sub = 
  Subscriber with properties:

                      TopicName: '/position'
                  LatestMessage: [1x1 Point]
                    MessageType: 'geometry_msgs/Point'
                     BufferSize: 1
    MessagePreprocessingEnabled: 0
                  NewMessageFcn: []
                     DataFormat: 'object'

pause(1);
sub.LatestMessage
ans = 
  ROS Point message with properties:

    MessageType: 'geometry_msgs/Point'
              X: 1
              Y: 2
              Z: 0

  Use showdetails to show the contents of the message

ROS 네트워크를 종료합니다.

rosshutdown
Shutting down global node /matlab_global_node_49233 with NodeURI http://dcc934856glnxa64:42035/ and MasterURI http://localhost:56013.
Shutting down ROS master on http://172.29.217.125:56013.

입력 인수

모두 축소

ROS publisher로, Publisher 객체 핸들로 지정됩니다. rospublisher를 사용하여 객체를 만들 수 있습니다.

ROS 메시지로, Message 객체 핸들 또는 구조체로 지정됩니다. rosmessage를 사용하여 객체를 만들 수 있습니다.

참고

향후 릴리스에서 ROS Toolbox는 ROS 메시지에 대해 객체 대신 메시지 구조체를 사용할 예정입니다.

지금 메시지 구조체를 사용하려면 "DataFormat" 이름-값 인수를 "struct"로 설정합니다. 자세한 내용은 ROS 메시지 구조체 항목을 참조하십시오.

확장 기능

버전 내역

R2019b에 개발됨

모두 확장