remove use of a macro that doesn't exist anymore

This commit is contained in:
Josh Faust 2010-11-09 23:33:25 +00:00
parent bc92f8bc90
commit 73f5eacdd7
3 changed files with 31 additions and 31 deletions

View File

@ -37,16 +37,16 @@ struct Clock_ : public ros::Message
private:
static const char* __s_getDataType_() { return "roslib/Clock"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
static const std::string __s_getDataType() { return __s_getDataType_(); }
ROSCPP_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
const std::string __getDataType() const { return __s_getDataType_(); }
private:
static const char* __s_getMD5Sum_() { return "a9c97c1d230cfc112e270351a944ee47"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
ROSCPP_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
private:
static const char* __s_getMessageDefinition_() { return "# roslib/Clock is used for publishing simulated time in ROS. \n\
@ -56,25 +56,25 @@ time clock\n\
\n\
"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
ROSCPP_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
ROSCPP_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
{
ros::serialization::OStream stream(write_ptr, 1000000000);
ros::serialization::serialize(stream, clock);
return stream.getData();
}
ROSCPP_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
virtual uint8_t *deserialize(uint8_t *read_ptr)
{
ros::serialization::IStream stream(read_ptr, 1000000000);
ros::serialization::deserialize(stream, clock);
return stream.getData();
}
ROSCPP_DEPRECATED virtual uint32_t serializationLength() const
virtual uint32_t serializationLength() const
{
uint32_t size = 0;
size += ros::serialization::serializationLength(clock);

View File

@ -47,16 +47,16 @@ struct Header_ : public ros::Message
private:
static const char* __s_getDataType_() { return "roslib/Header"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
static const std::string __s_getDataType() { return __s_getDataType_(); }
ROSCPP_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
const std::string __getDataType() const { return __s_getDataType_(); }
private:
static const char* __s_getMD5Sum_() { return "2176decaecbce78abc3b96ef049fabed"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
ROSCPP_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
private:
static const char* __s_getMessageDefinition_() { return "# Standard metadata for higher-level stamped data types.\n\
@ -77,11 +77,11 @@ string frame_id\n\
\n\
"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
ROSCPP_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
ROSCPP_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
{
ros::serialization::OStream stream(write_ptr, 1000000000);
ros::serialization::serialize(stream, seq);
@ -90,7 +90,7 @@ public:
return stream.getData();
}
ROSCPP_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
virtual uint8_t *deserialize(uint8_t *read_ptr)
{
ros::serialization::IStream stream(read_ptr, 1000000000);
ros::serialization::deserialize(stream, seq);
@ -99,7 +99,7 @@ public:
return stream.getData();
}
ROSCPP_DEPRECATED virtual uint32_t serializationLength() const
virtual uint32_t serializationLength() const
{
uint32_t size = 0;
size += ros::serialization::serializationLength(seq);

View File

@ -75,23 +75,23 @@ struct Log_ : public ros::Message
enum { ERROR = 8 };
enum { FATAL = 16 };
ROSCPP_DEPRECATED uint32_t get_topics_size() const { return (uint32_t)topics.size(); }
ROSCPP_DEPRECATED void set_topics_size(uint32_t size) { topics.resize((size_t)size); }
ROSCPP_DEPRECATED void get_topics_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->topics; }
ROSCPP_DEPRECATED void set_topics_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->topics = vec; }
uint32_t get_topics_size() const { return (uint32_t)topics.size(); }
void set_topics_size(uint32_t size) { topics.resize((size_t)size); }
void get_topics_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->topics; }
void set_topics_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->topics = vec; }
private:
static const char* __s_getDataType_() { return "roslib/Log"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
static const std::string __s_getDataType() { return __s_getDataType_(); }
ROSCPP_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
const std::string __getDataType() const { return __s_getDataType_(); }
private:
static const char* __s_getMD5Sum_() { return "acffd30cd6b6de30f120938c17c593fb"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
ROSCPP_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
private:
static const char* __s_getMessageDefinition_() { return "##\n\
@ -134,11 +134,11 @@ string frame_id\n\
\n\
"; }
public:
ROSCPP_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
ROSCPP_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
ROSCPP_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
{
ros::serialization::OStream stream(write_ptr, 1000000000);
ros::serialization::serialize(stream, header);
@ -152,7 +152,7 @@ public:
return stream.getData();
}
ROSCPP_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
virtual uint8_t *deserialize(uint8_t *read_ptr)
{
ros::serialization::IStream stream(read_ptr, 1000000000);
ros::serialization::deserialize(stream, header);
@ -166,7 +166,7 @@ public:
return stream.getData();
}
ROSCPP_DEPRECATED virtual uint32_t serializationLength() const
virtual uint32_t serializationLength() const
{
uint32_t size = 0;
size += ros::serialization::serializationLength(header);