ros / rosconsole

17 stars 61 forks source link

rosconsole: Add ROS_VERIFY counterpart to ROS_ASSERT #3

Open dirk-thomas opened 6 years ago

dirk-thomas commented 6 years ago

From @ablasdel on January 8, 2013 22:45

I've added macros ROS_VERIFY, ROS_VERIFY_MSG, and ROS_VERIFY_CMD which are similar to ROSASSERT*, except that they also execute the condition when asserts are disabled. This was inspired by BOOST_VERIFY. It's really useful to do things like:

ROS_VERIFY(someFunctionWhichShouldReturnTrue());

Patch attached.

change history (ros_assert.diff in the first ): Changed 2 years ago by mrinal

attachment ros_assert.diff added Patch to add ROSVERIFY* macros. Also includes tests for them.

migration of trac ticket: https://code.ros.org/trac/ros/ticket/3323

_Copied from original issue: ros/roscomm#71

dirk-thomas commented 6 years ago

From @ablasdel on January 8, 2013 22:46

ros_assert.diff content:

Index: test/verify_test_asserts_disabled.cpp
===================================================================
--- test/verify_test_asserts_disabled.cpp   (revision 0)
+++ test/verify_test_asserts_disabled.cpp   (revision 0)
@@ -0,0 +1,56 @@
+/*
+ * Copyright (c) 2011, CLMC Lab, University of Southern California
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ *     * Redistributions of source code must retain the above copyright
+ *       notice, this list of conditions and the following disclaimer.
+ *     * Redistributions in binary form must reproduce the above copyright
+ *       notice, this list of conditions and the following disclaimer in the
+ *       documentation and/or other materials provided with the distribution.
+ *     * Neither the name of Willow Garage, Inc. nor the names of its
+ *       contributors may be used to endorse or promote products derived from
+ *       this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+/** \author Mrinal Kalakrishnan */
+
+#define NDEBUG
+
+#include <ros/assert.h>
+#include <gtest/gtest.h>
+
+#include "verify_test.h"
+
+TEST(VerifyTest, assertsDisabled)
+{
+    counter = 0;
+    doVerifySuccess();
+    EXPECT_EQ(1, counter);
+
+    doVerifyFailure();
+    EXPECT_EQ(2, counter);
+}
+
+TEST(VerifyTest, assertsDisabledMessage)
+{
+    counter = 0;
+    doVerifyMessageSuccess();
+    EXPECT_EQ(1, counter);
+
+    doVerifyMessageFailure();
+    EXPECT_EQ(2, counter);
+}
Index: test/verify_test_asserts_enabled.cpp
===================================================================
--- test/verify_test_asserts_enabled.cpp    (revision 0)
+++ test/verify_test_asserts_enabled.cpp    (revision 0)
@@ -0,0 +1,49 @@
+/*
+ * Copyright (c) 2011, CLMC Lab, University of Southern California
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ *     * Redistributions of source code must retain the above copyright
+ *       notice, this list of conditions and the following disclaimer.
+ *     * Redistributions in binary form must reproduce the above copyright
+ *       notice, this list of conditions and the following disclaimer in the
+ *       documentation and/or other materials provided with the distribution.
+ *     * Neither the name of Willow Garage, Inc. nor the names of its
+ *       contributors may be used to endorse or promote products derived from
+ *       this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+/** \author Mrinal Kalakrishnan */
+
+#define ROS_ASSERT_ENABLED
+
+#include <ros/assert.h>
+#include <gtest/gtest.h>
+
+#include "verify_test.h"
+
+TEST(VerifyTest, assertsEnabled)
+{
+    doVerifySuccess();
+    EXPECT_DEATH(doVerifyFailure(), "ASSERTION FAILED");
+}
+
+TEST(VerifyTest, assertsEnabledMessage)
+{
+    doVerifyMessageSuccess();
+    EXPECT_DEATH(doVerifyMessageFailure(), "ASSERTION FAILED");
+}
+
Index: test/verify_test.cpp
===================================================================
--- test/verify_test.cpp    (revision 0)
+++ test/verify_test.cpp    (revision 0)
@@ -0,0 +1,42 @@
+/*
+ * Copyright (c) 2011, CLMC Lab, University of Southern California
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ *     * Redistributions of source code must retain the above copyright
+ *       notice, this list of conditions and the following disclaimer.
+ *     * Redistributions in binary form must reproduce the above copyright
+ *       notice, this list of conditions and the following disclaimer in the
+ *       documentation and/or other materials provided with the distribution.
+ *     * Neither the name of Willow Garage, Inc. nor the names of its
+ *       contributors may be used to endorse or promote products derived from
+ *       this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/** \author Mrinal Kalakrishnan */
+
+#include <gtest/gtest.h>
+#include <ros/time.h>
+
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  ros::Time::init();
+  testing::FLAGS_gtest_death_test_style = "threadsafe";
+
+  return RUN_ALL_TESTS();
+}
Index: test/verify_test.h
===================================================================
--- test/verify_test.h  (revision 0)
+++ test/verify_test.h  (revision 0)
@@ -0,0 +1,75 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+*  Copyright (c) 2011, CLMC Lab, University of Southern California
+*  All rights reserved.
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*   * Redistributions of source code must retain the above copyright
+*     notice, this list of conditions and the following disclaimer.
+*   * Redistributions in binary form must reproduce the above
+*     copyright notice, this list of conditions and the following
+*     disclaimer in the documentation and/or other materials provided
+*     with the distribution.
+*   * Neither the name of the Willow Garage nor the names of its
+*     contributors may be used to endorse or promote products derived
+*     from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+*  POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+/** \author Mrinal Kalakrishnan */
+
+
+#ifndef VERIFY_TEST_H_
+#define VERIFY_TEST_H_
+
+static int counter=0;
+
+static bool incCounterSuccess()
+{
+    ++counter;
+    return true;
+}
+
+static bool incCounterFailure()
+{
+    ++counter;
+    return false;
+}
+
+static void doVerifySuccess()
+{
+  ROS_VERIFY(incCounterSuccess());
+}
+
+static void doVerifyFailure()
+{
+  ROS_VERIFY(incCounterFailure());
+}
+
+static void doVerifyMessageSuccess()
+{
+  ROS_VERIFY_MSG(incCounterSuccess(), "Testing %d %d %d", 1, 2, 3);
+}
+
+static void doVerifyMessageFailure()
+{
+  ROS_VERIFY_MSG(incCounterFailure(), "Testing %d %d %d", 1, 2, 3);
+}
+
+#endif /* VERIFY_TEST_H_ */
Index: include/ros/assert.h
===================================================================
--- include/ros/assert.h    (revision 13189)
+++ include/ros/assert.h    (working copy)
@@ -89,6 +89,18 @@
  * Currently implemented for Windows (any platform), powerpc64, and x86
  */

+/** \def ROS_VERIFY(cond)
+ * \brief Similar to ROS_ASSERT, but executes "cond" even if asserts are disabled.
+ */
+
+/** \def ROS_VERIFY_MSG(cond, ...)
+ * \brief Similar to ROS_ASSERT_MSG, but executes "cond" even if asserts are disabled.
+ */
+
+/** \def ROS_VERIFY_CMD(cond, cmd)
+ * \brief Similar to ROS_ASSERT_CMD, but executes "cond" even if asserts are disabled.
+ */
+
 #ifdef WIN32
 # define ROS_ISSUE_BREAK() __debugbreak();
 #elif defined(__powerpc64__)
@@ -136,12 +148,23 @@
     } \
   } while (0)

+#define ROS_VERIFY(cond) \
+  ROS_ASSERT(cond)

+#define ROS_VERIFY_MSG(cond, ...) \
+  ROS_ASSERT_MSG(cond, __VA_ARGS__)
+
+#define ROS_VERIFY_CMD(cond, cmd) \
+  ROS_ASSERT_CMD(cond, cmd)
+
 #else
 #define ROS_BREAK()
 #define ROS_ASSERT(cond)
 #define ROS_ASSERT_MSG(cond, ...)
 #define ROS_ASSERT_CMD(cond, cmd)
+#define ROS_VERIFY(cond) ((void)(cond))
+#define ROS_VERIFY_MSG(cond, ...) ((void)(cond))
+#define ROS_VERIFY_CMD(cond, cmd) ((void)(cond))
 #endif

 #endif // ROSCONSOLE_ROSASSERT_H
Index: CMakeLists.txt
===================================================================
--- CMakeLists.txt  (revision 13189)
+++ CMakeLists.txt  (working copy)
@@ -25,6 +25,13 @@
 if(${CMAKE_SYSTEM_NAME} STREQUAL Linux)
   rosbuild_add_gtest(test/assertion_test test/assertion_test.cpp)
   target_link_libraries(test/assertion_test ${PROJECT_NAME})
+
+  rosbuild_add_gtest(test/verify_test
+    test/verify_test_asserts_disabled.cpp
+    test/verify_test_asserts_enabled.cpp
+    test/verify_test.cpp
+  )
+  target_link_libraries(test/verify_test ${PROJECT_NAME})
 endif(${CMAKE_SYSTEM_NAME} STREQUAL Linux)

 rosbuild_add_gtest(test/thread_test test/thread_test.cpp)
dirk-thomas commented 6 years ago

From @ffurrer on April 20, 2015 12:39

Any update on this, or ideas of integrating glog (https://github.com/google/glog) analogies?

dirk-thomas commented 6 years ago

There is no progress and and it is not likely that the maintainers will have the time to work on it. Therefore the ticket is marked with the milestone "untargete" (https://github.com/ros/ros_comm/milestones).