Skip to content

Commit

Permalink
Fix: release with debug bag recorder MOVEMENT-999 (#20)
Browse files Browse the repository at this point in the history
* Improves lunar-devel jenkins test stability (backport to kinetic-devel) (ros#1578)

* extend timeout for sensitive python test

* compression ratio test threshold relaxed

* removed accidental test race condition

* relaxes bag compression-ratio test threshold more

* fix compiler warnings about unused variables (ros#1428) (ros#1576)

* feat: building in debug mode

* feat: building in debug mode

* feat: building in debug mode

* fix:

* fix: fixing tests

* fix: fixing tests

* fix: fixing tests

* feat: building in debug mode

* feat: building in debug mode

* feat: building in debug mode

* fix:

* fix: fixing tests

* fix: fixing tests

* fix: fixing tests

* fix: adding test_rosmaster dependency to rosmsg

* fix: release is failing. trying with release versions

* fix: excluding local_setup.sh from the build

* fix: printing version of boost

* fix: changing to debug build

* fix: adding more debugging info around the starting / stopping of bags

* feat: changing build type to RelWithDebInfo
  • Loading branch information
mbittarelli6river authored Nov 26, 2019
1 parent b227ac7 commit b55c80a
Show file tree
Hide file tree
Showing 17 changed files with 41 additions and 38 deletions.
3 changes: 2 additions & 1 deletion build.sh
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@ source /opt/ros/kinetic/setup.bash
catkin_init_workspace
cd ..
pwd
catkin_make -DCMAKE_BUILD_TYPE=Release -j8 install

catkin_make -DCMAKE_BUILD_TYPE=RelWithDebInfo -j8 install

apt-get update
apt-get install -y git curl ruby ruby-dev rubygems libffi-dev build-essential
Expand Down
2 changes: 0 additions & 2 deletions clients/roscpp/src/libros/init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -604,8 +604,6 @@ void shutdown()
XMLRPCManager::instance()->shutdown();
}

WallTime end = WallTime::now();

g_started = false;
g_ok = false;
Time::shutdown();
Expand Down
2 changes: 1 addition & 1 deletion test/test_rosbag/bag_migration_tests/test/random_play.py
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ def test_random_play(self):
# these bounds are much larger than they ought to be, but
# you never know with a heavily loaded system.
self.assertTrue(input_time - expect_time > -.5)
self.assertTrue(abs(input_time - expect_time) < .5)
self.assertTrue(abs(input_time - expect_time) < 5.0)
break

if not msg_match:
Expand Down
1 change: 1 addition & 0 deletions test/test_rosbag/test/test_bag.cpp.in
Original file line number Diff line number Diff line change
Expand Up @@ -376,6 +376,7 @@ TEST(rosbag, bad_topic_query_works) {

rosbag::View view(bag, rosbag::TopicQuery(t));
foreach(rosbag::MessageInstance const m, view) {
(void)m;
FAIL();
}

Expand Down
4 changes: 2 additions & 2 deletions test/test_rosbag/test/test_bag.py
Original file line number Diff line number Diff line change
Expand Up @@ -324,8 +324,8 @@ def test_get_compression_info(self):

# the value varies each run, I suspect based on rand, but seems
# to generally be around 960 to 980 on my comp
self.assertLess(info.compressed, 1000)
self.assertGreater(info.compressed, 900)
self.assertLess(info.compressed, 1050)
self.assertGreater(info.compressed, 850)

def test_get_time(self):
fn = '/tmp/test_get_time.bag'
Expand Down
4 changes: 2 additions & 2 deletions test/test_rosbag_storage/src/swap_bags.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,13 +72,13 @@ void readBags(rosbag::CompressionType a, rosbag::CompressionType b) {
BOOST_FOREACH(rosbag::MessageInstance const m, a_view)
{
std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
ASSERT_TRUE(i);
ASSERT_TRUE(i != nullptr);
EXPECT_EQ(i->data, a);
}
BOOST_FOREACH(rosbag::MessageInstance const m, b_view)
{
std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
ASSERT_TRUE(i);
ASSERT_TRUE(i != nullptr);
EXPECT_EQ(i->data, b);
}
}
Expand Down
8 changes: 4 additions & 4 deletions test/test_roscpp/test/src/intraprocess_subscriptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ TEST(IntraprocessSubscriptions, noCopy)
ros::Duration(0.01).sleep();
}

ASSERT_TRUE(g_msg);
ASSERT_TRUE(g_msg != nullptr);
EXPECT_EQ(g_msg.get(), msg.get());
EXPECT_FALSE(g_msg->serialized);
EXPECT_FALSE(g_msg->deserialized);
Expand Down Expand Up @@ -236,7 +236,7 @@ TEST(IntraprocessSubscriptions, differentRTTI)
ros::Duration(0.01).sleep();
}

ASSERT_TRUE(g_msg);
ASSERT_TRUE(g_msg != nullptr);
EXPECT_NE((void*)g_msg.get(), (void*)msg.get());
EXPECT_TRUE(msg->serialized);
EXPECT_TRUE(g_msg->deserialized);
Expand Down Expand Up @@ -274,12 +274,12 @@ TEST(IntraprocessSubscriptions, noCopyAndDifferentRTTI)
ros::Duration(0.01).sleep();
}

ASSERT_TRUE(g_msg);
ASSERT_TRUE(g_msg != nullptr);
EXPECT_NE((void*)g_msg.get(), (void*)msg.get());
EXPECT_TRUE(msg->serialized);
EXPECT_TRUE(g_msg->deserialized);

ASSERT_TRUE(g_msg2);
ASSERT_TRUE(g_msg2 != nullptr);
EXPECT_EQ(g_msg2.get(), msg.get());
EXPECT_TRUE(g_msg2->serialized);
EXPECT_FALSE(g_msg2->deserialized);
Expand Down
8 changes: 4 additions & 4 deletions test/test_roscpp/test/src/nonconst_subscriptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ TEST(NonConstSubscriptions, oneNonConstSubscriber)
pub.publish(msg);
ros::spinOnce();

ASSERT_TRUE(h.message_);
ASSERT_TRUE(h.message_ != nullptr);
EXPECT_EQ(h.message_, msg);
}

Expand All @@ -92,7 +92,7 @@ TEST(NonConstSubscriptions, oneConstOneNonConst)
pub.publish(msg);
ros::spinOnce();

ASSERT_TRUE(h.message_);
ASSERT_TRUE(h.message_ != nullptr);
EXPECT_NE(h.message_, msg);
EXPECT_EQ(h2.message_, msg);
}
Expand All @@ -110,7 +110,7 @@ TEST(NonConstSubscriptions, twoNonConst)
pub.publish(msg);
ros::spinOnce();

ASSERT_TRUE(h.message_);
ASSERT_TRUE(h.message_ != nullptr);
EXPECT_NE(h.message_, msg);
}

Expand All @@ -127,7 +127,7 @@ TEST(NonConstSubscriptions, twoConst)
pub.publish(msg);
ros::spinOnce();

ASSERT_TRUE(h.message_);
ASSERT_TRUE(h.message_ != nullptr);
EXPECT_EQ(h.message_, msg);
EXPECT_EQ(h2.message_, msg);
}
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/wait_for_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ TEST(Roscpp, waitForMessage)
ros::Publisher pub = nh.advertise<TestArray>("test", 1, true);
pub.publish(TestArray());
TestArrayConstPtr msg = topic::waitForMessage<TestArray>("test");
ASSERT_TRUE(msg);
ASSERT_TRUE(msg != nullptr);
}

TEST(Roscpp, waitForMessageWithTimeout)
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/test_callback_queue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -439,9 +439,8 @@ void ConditionObject::add()
{
while(!condition_stop.load())
{
if(condition_sync.load())
if(condition_sync.load() && queue->isEmpty())
{
condition_sync.store(false);
condition_one.store(true);
id++;
queue->addCallback(boost::make_shared<RaceConditionCallback>(this, &id), id);
Expand All @@ -458,6 +457,7 @@ TEST(CallbackQueue, raceConditionCallback)
boost::thread t(boost::bind(&ConditionObject::add, &condition_object));
for(unsigned int i = 0; i < 1000000; ++i)
{
condition_object.condition_sync.store(false);
if (queue.callOne() == CallbackQueue::Called)
{
if(condition_object.condition_one.load())
Expand Down
2 changes: 2 additions & 0 deletions tools/rosbag/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@ find_package(BZip2 REQUIRED)

catkin_python_setup()

# set(CMAKE_BUILD_TYPE Debug)

# Support large bags (>2GB) on 32-bit systems
add_definitions(-D_FILE_OFFSET_BITS=64)

Expand Down
1 change: 1 addition & 0 deletions tools/rosmsg/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<run_depend>roslib</run_depend>

<test_depend>std_msgs</test_depend>
<test_depend>test_rosmaster</test_depend>

<export>
<rosdoc config="rosdoc.yaml"/>
Expand Down
12 changes: 6 additions & 6 deletions utilities/message_filters/test/test_approximate_time_policy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,8 @@ class ApproximateTimeSynchronizerTest
{
//printf("Call_back called\n");
//printf("Call back: <%f, %f>\n", p->header.stamp.toSec(), q->header.stamp.toSec());
ASSERT_TRUE(p);
ASSERT_TRUE(q);
ASSERT_TRUE(p != nullptr);
ASSERT_TRUE(q != nullptr);
ASSERT_LT(output_position_, output_.size());
EXPECT_EQ(output_[output_position_].first, p->header.stamp);
EXPECT_EQ(output_[output_position_].second, q->header.stamp);
Expand Down Expand Up @@ -164,10 +164,10 @@ class ApproximateTimeSynchronizerTestQuad
{
//printf("Call_back called\n");
//printf("Call back: <%f, %f>\n", p->header.stamp.toSec(), q->header.stamp.toSec());
ASSERT_TRUE(p);
ASSERT_TRUE(q);
ASSERT_TRUE(r);
ASSERT_TRUE(s);
ASSERT_TRUE(p != nullptr);
ASSERT_TRUE(q != nullptr);
ASSERT_TRUE(r != nullptr);
ASSERT_TRUE(s != nullptr);
ASSERT_LT(output_position_, output_.size());
EXPECT_EQ(output_[output_position_].time[0], p->header.stamp);
EXPECT_EQ(output_[output_position_].time[1], q->header.stamp);
Expand Down
8 changes: 4 additions & 4 deletions utilities/message_filters/test/test_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ TEST(Chain, retrieveFilter)

c.addFilter(boost::make_shared<PassThrough<Msg> >());

ASSERT_TRUE(c.getFilter<PassThrough<Msg> >(0));
ASSERT_TRUE(c.getFilter<PassThrough<Msg> >(0) != nullptr);
ASSERT_FALSE(c.getFilter<PassThrough<Msg> >(1));
}

Expand All @@ -161,7 +161,7 @@ TEST(Chain, retrieveFilterThroughBaseClass)

c.addFilter(boost::make_shared<PassThrough<Msg> >());

ASSERT_TRUE(cb->getFilter<PassThrough<Msg> >(0));
ASSERT_TRUE(cb->getFilter<PassThrough<Msg> >(0) != nullptr);
ASSERT_FALSE(cb->getFilter<PassThrough<Msg> >(1));
}

Expand All @@ -174,8 +174,8 @@ TEST(Chain, retrieveBaseClass)
{
Chain<Msg> c;
c.addFilter(boost::make_shared<PTDerived>());
ASSERT_TRUE(c.getFilter<PassThrough<Msg> >(0));
ASSERT_TRUE(c.getFilter<PTDerived>(0));
ASSERT_TRUE(c.getFilter<PassThrough<Msg> >(0) != nullptr);
ASSERT_TRUE(c.getFilter<PTDerived>(0) != nullptr);
}

int main(int argc, char **argv){
Expand Down
4 changes: 2 additions & 2 deletions utilities/message_filters/test/test_exact_time_policy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,8 +187,8 @@ TEST(ExactTime, eventInEventOut)
sync.add<0>(evt);
sync.add<1>(evt);

ASSERT_TRUE(h.e1_.getMessage());
ASSERT_TRUE(h.e2_.getMessage());
ASSERT_TRUE(h.e1_.getMessage() != nullptr);
ASSERT_TRUE(h.e2_.getMessage() != nullptr);
ASSERT_EQ(h.e1_.getReceiptTime(), evt.getReceiptTime());
ASSERT_EQ(h.e2_.getReceiptTime(), evt.getReceiptTime());
}
Expand Down
10 changes: 5 additions & 5 deletions utilities/message_filters/test/test_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ TEST(Subscriber, singleNonConstCallback)

ros::spinOnce();

ASSERT_TRUE(h.msg_);
ASSERT_TRUE(h.msg_ != nullptr);
ASSERT_EQ(msg.get(), h.msg_.get());
}

Expand All @@ -169,8 +169,8 @@ TEST(Subscriber, multipleNonConstCallbacksFilterSubscriber)

ros::spinOnce();

ASSERT_TRUE(h.msg_);
ASSERT_TRUE(h2.msg_);
ASSERT_TRUE(h.msg_ != nullptr);
ASSERT_TRUE(h2.msg_ != nullptr);
EXPECT_NE(msg.get(), h.msg_.get());
EXPECT_NE(msg.get(), h2.msg_.get());
EXPECT_NE(h.msg_.get(), h2.msg_.get());
Expand All @@ -189,8 +189,8 @@ TEST(Subscriber, multipleCallbacksSomeFilterSomeDirect)

ros::spinOnce();

ASSERT_TRUE(h.msg_);
ASSERT_TRUE(h2.msg_);
ASSERT_TRUE(h.msg_ != nullptr);
ASSERT_TRUE(h2.msg_ != nullptr);
EXPECT_NE(msg.get(), h.msg_.get());
EXPECT_NE(msg.get(), h2.msg_.get());
EXPECT_NE(h.msg_.get(), h2.msg_.get());
Expand Down
4 changes: 2 additions & 2 deletions utilities/message_filters/test/time_synchronizer_unittest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -516,8 +516,8 @@ TEST(TimeSynchronizer, eventInEventOut)
sync.add<0>(evt);
sync.add<1>(evt);

ASSERT_TRUE(h.e1_.getMessage());
ASSERT_TRUE(h.e2_.getMessage());
ASSERT_TRUE(h.e1_.getMessage() != nullptr);
ASSERT_TRUE(h.e2_.getMessage() != nullptr);
ASSERT_EQ(h.e1_.getReceiptTime(), evt.getReceiptTime());
ASSERT_EQ(h.e2_.getReceiptTime(), evt.getReceiptTime());
}
Expand Down

0 comments on commit b55c80a

Please sign in to comment.