ROS msg Header
이전 시간에 메시지와 서비스 파일을 생성하고, 각각의 언어로 빌드하는 시간을 가졌습니다. 오늘은 해당 파일이 어떻게 변환되었는지, 헤더 파일의 구조를 알아보도록 하겠습니다.
먼저, 이전 시간에 생성한 Num.msg
메시지 파일 내용은 다음과 같습니다.
int64 num
해당 파일은 catkin_make
를 거치면 C++ 기준 ~/catkin_ws/devel/include/<procject_name>/Num.h
가 됩니다. 헤더 파일의 내용은 다음과 같습니다. (ROS Noetic 기준)
// Generated by gencpp from file beginner_tutorials/Num.msg
// DO NOT EDIT!
// 헤더 중복 방지를 위한 매크로
#ifndef BEGINNER_TUTORIALS_MESSAGE_NUM_H
#define BEGINNER_TUTORIALS_MESSAGE_NUM_H
// 메시지가 어떤 자료형을 쓰던 일단 include 하고 봅니다.
#include <string>
#include <vector>
#include <map>
// ros 헤더 파일도 불러옵니다.
#include <ros/types.h>
#include <ros/serialization.h>
#include <ros/builtin_message_traits.h>
#include <ros/message_operations.h>
// 이름 중복 방지를 위해 프로젝트 명을 namespace로 사용합니다.
namespace beginner_tutorials {
// template를 사용하여 다양한 자료형에 대응합니다.
template <class ContainerAllocator>
struct Num_ {
typedef Num_<ContainerAllocator> Type;
// int64_t 자료형의 멤버변수 num을 0으로 초기화합니다.
Num_(): num(0) {}
Num_(const ContainerAllocator& _alloc): num(0) {
(void)_alloc;
}
// int64_t 자료형에 별칭을 붙인 뒤, 멤버변수 num을 해당 자료형으로 선언합니다.
typedef int64_t _num_type;
_num_type num;
// boost 라이브러리는 C++ 라이브러리 중 안정성과 성능이 높고 라이선스가 자유로워 오픈소스 프로젝트에서 자주 사용됩니다.
// C++11부터 추가된 shared_ptr을 사용하여 Num_를 가리키는 포인터 객체를 생성합니다. 여러 shared_ptr의 가리키는 대상은 동일할 수 있습니다.
typedef boost::shared_ptr< ::beginner_tutorials::Num_<ContainerAllocator> > Ptr;
// const를 붙이면 포인터를 이용하여 해당 객체를 변경할 수 없습니다. 포인터가 가리키는 값은 바꿀 수 있습니다.
typedef boost::shared_ptr< ::beginner_tutorials::Num_<ContainerAllocator> const> ConstPtr;
}; // struct Num_
// Num_<allocator<void>>의 별칭으로 Num을 지정합니다.
// allocator 클래스는 void 형식에 대한 클래스 템플릿 할당자를 명시적으로 특수화합니다. 생성자와 대입 연산자는 클래스 템플릿과 동일하게 동작합니다.
typedef ::beginner_tutorials::Num_<std::allocator<void> > Num;
// Num을 가리키는 shared_ptr 포인터 객체를 정의합니다.
typedef boost::shared_ptr< ::beginner_tutorials::Num > NumPtr;
// NumConstPtr이 가리키는 객체는 해당 포인터 변수로 값을 변경할 수 없습니다.
typedef boost::shared_ptr< ::beginner_tutorials::Num const> NumConstPtr;
// constants requiring out of line definition
// stream 출력 overload
template<typename ContainerAllocator>
std::ostream& operator<<(std::ostream& s, const ::beginner_tutorials::Num_<ContainerAllocator> & v) {
ros::message_operations::Printer< ::beginner_tutorials::Num_<ContainerAllocator> >::stream(s, "", v);
return s;
}
// == overload
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::beginner_tutorials::Num_<ContainerAllocator1> & lhs, const ::beginner_tutorials::Num_<ContainerAllocator2> & rhs) {
return lhs.num == rhs.num;
}
// != overload
// == 결과값에 not을 취합니다.
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::beginner_tutorials::Num_<ContainerAllocator1> & lhs, const ::beginner_tutorials::Num_<ContainerAllocator2> & rhs) {
return !(lhs == rhs);
}
} // namespace beginner_tutorials
namespace ros {
// 메시지 특성에 대해 정의한 namespace입니다. ros/builtin_message_traits.h에 정의된 TrueType, FalseType을 상속합니다.
// message traits는 C++ type을 ROS msg type에 적용하는데 주로 사용되지만, datatype, md5sum, full message definition을 얻을 때에도 유용합니다.
// advertise/subscribe 하기 위해선 MD5Sum, DataType, Definition 속성이 반드시 필요합니다.
namespace message_traits {
// TrueType은 멤버변수 value로 true, type으로 TrueType을 가지고 있습니다.
template <class ContainerAllocator>
struct IsMessage< ::beginner_tutorials::Num_<ContainerAllocator> >: TrueType {};
// 메시지가 맞기 때문에 TrueType을 상속합니다.
template <class ContainerAllocator>
struct IsMessage< ::beginner_tutorials::Num_<ContainerAllocator> const>: TrueType {};
// int64_t는 64bit으로 크기가 정해져 있기 때문에 true입니다.
template <class ContainerAllocator>
struct IsFixedSize< ::beginner_tutorials::Num_<ContainerAllocator> >: TrueType {};
// const 버전
template <class ContainerAllocator>
struct IsFixedSize< ::beginner_tutorials::Num_<ContainerAllocator> const>: TrueType {};
// Header header가 없기 때문에 false
template <class ContainerAllocator>
struct HasHeader< ::beginner_tutorials::Num_<ContainerAllocator> >: FalseType {};
// const 버전
template <class ContainerAllocator>
struct HasHeader< ::beginner_tutorials::Num_<ContainerAllocator> const>: FalseType {};
// advertise/subscribe 하기 위해 반드시 필요합니다.
template<class ContainerAllocator>
struct MD5Sum< ::beginner_tutorials::Num_<ContainerAllocator> > {
// md5sum 값을 반환합니다.
static const char* value() {
return "57d3c40ec3ac3754af76a83e6e73127a";
}
// const + 참조자 버전
static const char* value(const ::beginner_tutorials::Num_<ContainerAllocator>&) { return value(); }
// 8 byte = QWORD
static const uint64_t static_value1 = 0x57d3c40ec3ac3754ULL;
// 8 byte = QWORD
static const uint64_t static_value2 = 0xaf76a83e6e73127aULL;
};
// advertise/subscribe 하기 위해 반드시 필요합니다.
template<class ContainerAllocator>
struct DataType< ::beginner_tutorials::Num_<ContainerAllocator> > {
// 패키지이름/메시지 파일 이름을 value 메소드 반환값으로 지니고 있습니다.
static const char* value() {
return "beginner_tutorials/Num";
}
// const + 참조자 버전
static const char* value(const ::beginner_tutorials::Num_<ContainerAllocator>&) { return value(); }
};
// advertise/subscribe 하기 위해 반드시 필요합니다.
template<class ContainerAllocator>
struct Definition< ::beginner_tutorials::Num_<ContainerAllocator> > {
// msg 파일 내용을 value 메소드 반환값으로 지니고 있습니다.
static const char* value() {
return "int64 num\n";
}
// const + 참조자 버전
static const char* value(const ::beginner_tutorials::Num_<ContainerAllocator>&) { return value(); }
};
} // namespace message_traits
} // namespace ros
namespace ros {
namespace serialization {
template<class ContainerAllocator> struct Serializer< ::beginner_tutorials::Num_<ContainerAllocator> > {
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) {
stream.next(m.num);
}
ROS_DECLARE_ALLINONE_SERIALIZER
}; // struct Num_
} // namespace serialization
} // namespace ros
namespace ros {
namespace message_operations {
// 메시지를 출력합니다. 주어진 indent로 값을 구분합니다.
template<class ContainerAllocator>
struct Printer< ::beginner_tutorials::Num_<ContainerAllocator> > {
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::beginner_tutorials::Num_<ContainerAllocator>& v) {
s << indent << "num: ";
Printer<int64_t>::stream(s, indent + " ", v.num);
}
};
} // namespace message_operations
} // namespace ros
#endif // BEGINNER_TUTORIALS_MESSAGE_NUM_H
여기서 우리가 사용하는 부분은 namespace beginner_tutorials
의 Num
자료형입니다. 또한, advertise/subscribe 하기 위해 반드시 필요한 속성으로는 MD5SUM
, Definition
, DataType
이 반드시 필요함을 알 수 있습니다.
해당 타입이 ROS advertise 과정에서 어떻게 사용되는지 알아보겠습니다.
// in ros/node_handle.h
// Representative Version of advertise()
template <class M>
Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false) {
AdvertiseOptions ops;
ops.template init<M>(topic, queue_size);
ops.latch = latch;
return advertise(ops);
}
템플릿에 사용된 class M
이 우리가 전달한 메시지 자료형입니다. 이는 각각 AdvertiseOption/SubscribeOption 형태의 변수 ops를 init 하기 위해 사용됩니다.
// in ros/advertise_options.h
template <class M>
void init(const std::string& _topic, uint32_t _queue_size,
const SubscriberStatusCallback& _connect_cb = SubscriberStatusCallback(),
const SubscriberStatusCallback& _disconnect_cb = SubscriberStatusCallback()) {
topic = _topic;
queue_size = _queue_size;
connect_cb = _connect_cb;
disconnect_cb = _disconnect_cb;
md5sum = message_traits::md5sum<M>();
datatype = message_traits::datatype<M>();
message_definition = message_traits::definition<M>();
has_header = message_traits::hasHeader<M>();
}
ops는 멤버변수 md5sum
, datatype
, message_definition
을 갖는데, 이때 message_traits가 사용됩니다. ops는 다시 publisher/subscriber를 만드는데 사용됩니다.
// in ros/node_handle.cpp
Publisher NodeHandle::advertise(AdvertiseOptions& ops) {
ops.topic = resolveName(ops.topic);
if (ops.callback_queue == 0) {
if (callback_queue_) {
ops.callback_queue = callback_queue_;
}
else {
ops.callback_queue = getGlobalCallbackQueue();
}
}
SubscriberCallbacksPtr callbacks(
new SubscriberCallbacks(
ops.connect_cb,
ops.disconnect_cb,
ops.tracked_object,
ops.callback_queue
)
);
// TopicManagerPtr의 advertise 과정에서도 md5sum, datatype, message_definition이 사용된다.
if (TopicManager::instance()->advertise(ops, callbacks)) {
// md5sum, datatype이 사용되었다!
Publisher pub(ops.topic, ops.md5sum, ops.datatype, *this, callbacks);
{
boost::mutex::scoped_lock lock(collection_->mutex_);
collection_->pubs_.push_back(pub.impl_);
}
return pub;
}
return Publisher();
}
bool TopicManager::advertise(const AdvertiseOptions& ops, const SubscriberCallbacksPtr& callbacks) {
if (ops.datatype == "*") {
std::stringstream ss;
ss << "Advertising with * as the datatype is not allowed. Topic [" << ops.topic << "]";
throw InvalidParameterException(ss.str());
}
if (ops.md5sum == "*") {
std::stringstream ss;
ss << "Advertising with * as the md5sum is not allowed. Topic [" << ops.topic << "]";
throw InvalidParameterException(ss.str());
}
if (ops.md5sum.empty()) {
throw InvalidParameterException("Advertising on topic [" + ops.topic + "] with an empty md5sum");
}
if (ops.datatype.empty()) {
throw InvalidParameterException("Advertising on topic [" + ops.topic + "] with an empty datatype");
}
if (ops.message_definition.empty()) {
ROS_WARN("Advertising on topic [%s] with an empty message definition. Some tools (e.g. rosbag) may not work correctly.", ops.topic.c_str());
}
// ...
}
이렇듯 해당 정보가 없을 경우 publisher 생성 과정에서 경고가 나오며, 이런 정보가 갖춰져 있기에 메시지 type을 통해 전체 스펙을 얻을 수 있다.
# package rosmsg
def get_msg_text(type_, raw=False, rospack=None):
"""
Get .msg file for type_ as text
:param type_: message type, ``str``
:param raw: if True, include comments and whitespace (default False), ``bool``
:returns: text of .msg file, ``str``
:raises :exc:`ROSMsgException` If type_ is unknown
"""
if rospack is None:
rospack = rospkg.RosPack()
search_path = {}
for p in rospack.list():
package_paths = _get_package_paths(p, rospack)
search_path[p] = [os.path.join(d, 'msg') for d in package_paths]
context = genmsg.MsgContext.create_default()
try:
spec = genmsg.load_msg_by_type(context, type_, search_path)
genmsg.load_depends(context, spec, search_path)
except Exception as e:
raise ROSMsgException("Unable to load msg [%s]: %s"%(type_, e))
if raw:
return spec.text
else:
return spec_to_str(context, spec)
'Robotics' 카테고리의 다른 글
18일차 - ROS NodeJS 서비스 서버/클라이언트 만들기 (0) | 2020.07.19 |
---|---|
17일차 - 메시지, 서비스, 액션 만들기 (0) | 2020.07.19 |
15일차 - ROS msg, srv 만들기 (0) | 2020.07.17 |
14일차 - ROS Melodic 마이그레이션 가이드 (0) | 2020.07.14 |
14일차 - 딜리버리 서비스 로봇 만들기 1 (0) | 2020.07.14 |