35 #include <gtest/gtest.h> 59 namespace message_traits
76 for (
unsigned int i=start; i < end; i++)
94 ASSERT_EQ(interval_data.size(), (
unsigned int) 3) ;
95 EXPECT_EQ(interval_data[0]->data, 1) ;
96 EXPECT_EQ(interval_data[1]->data, 2) ;
97 EXPECT_EQ(interval_data[2]->data, 3) ;
101 EXPECT_EQ(interval_data.size(), (
unsigned int) 0) ;
106 EXPECT_EQ(interval_data.size(), (
unsigned int) 0) ;
114 vector<boost::shared_ptr<Msg const> > interval_data;
116 ASSERT_EQ(interval_data.size(), (
unsigned int) 4);
117 EXPECT_EQ(interval_data[0]->data, 1);
118 EXPECT_EQ(interval_data[1]->data, 2);
119 EXPECT_EQ(interval_data[2]->data, 3);
120 EXPECT_EQ(interval_data[3]->data, 4);
123 ASSERT_EQ(interval_data.size(), (
unsigned int) 4);
124 EXPECT_EQ(interval_data[0]->data, 1);
127 ASSERT_EQ(interval_data.size(), (
unsigned int) 2);
128 EXPECT_EQ(interval_data[0]->data, 3);
129 EXPECT_EQ(interval_data[1]->data, 4);
132 ASSERT_EQ(interval_data.size(), (
unsigned int) 1);
133 EXPECT_EQ(interval_data[0]->data, 5);
159 ASSERT_EQ(interval_data.size(), (
unsigned int) 2) ;
160 EXPECT_EQ(interval_data[0]->data, 0) ;
161 EXPECT_EQ(interval_data[1]->data, 1) ;
165 ASSERT_EQ(interval_data.size(), (
unsigned int) 5) ;
166 EXPECT_EQ(interval_data[0]->data, 0) ;
167 EXPECT_EQ(interval_data[1]->data, 1) ;
168 EXPECT_EQ(interval_data[2]->data, 2) ;
169 EXPECT_EQ(interval_data[3]->data, 3) ;
170 EXPECT_EQ(interval_data[4]->data, 7) ;
183 ASSERT_FALSE(!elem_ptr) ;
184 EXPECT_EQ(elem_ptr->data, 9) ;
187 ASSERT_FALSE(!elem_ptr) ;
188 EXPECT_EQ(elem_ptr->data, 8) ;
191 EXPECT_TRUE(!elem_ptr) ;
219 int main(
int argc,
char **argv){
220 testing::InitGoogleTest(&argc, argv);
223 return RUN_ALL_TESTS();
boost::shared_ptr< Msg const > MsgConstPtr
boost::shared_ptr< M > getMessage() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
MConstPtr getElemBeforeTime(const ros::Time &time) const
Grab the newest element that occurs right before the specified time.
ros::MessageEvent< Msg const > event_
MConstPtr getElemAfterTime(const ros::Time &time) const
Grab the oldest element that occurs right after the specified time.
static ros::Time value(const Msg &m)
std::vector< MConstPtr > getSurroundingInterval(const ros::Time &start, const ros::Time &end) const
Retrieve the smallest interval of messages that surrounds an interval from start to end...
int main(int argc, char **argv)
void cb(const ros::MessageEvent< Msg const > &evt)
boost::shared_ptr< Msg const > buildMsg(double time, int data)
std::vector< MConstPtr > getInterval(const ros::Time &start, const ros::Time &end) const
Receive a vector of messages that occur between a start and end time (inclusive). ...
ros::Time getReceiptTime() const
Stores a time history of messages.
void fillCacheEasy(Cache< Msg > &cache, unsigned int start, unsigned int end)
TEST(Cache, easyInterval)
void add(const MConstPtr &msg)
Add a message to the cache, and pop off any elements that are too old. This method is registered with...
Connection registerCallback(const C &callback)
Register a callback to be called when this filter has passed.