ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Colcon test not running gtests

asked 2022-04-22 04:06:37 -0500

mrbh gravatar image

I am busy doing an assignment for school however I am running into an issue. I have a very basic proof of concept to which I have created a test using the google test framework.

When I run colcon test and colcon test-result it says "Summary: 4 tests, 0 errors, 0 failures, 0 skipped". These 4 tests however, aren't my created tests for the package. One of my own created tests is a deliberate fail to check if colcon test-result also shows that it failed, which it did not.

I think there might be an issue with my CMakeLists.txt, but I am not certain and do not have a lot of experience with cmake.

See my code here:

driverobot.hpp

#ifndef DRIVEROBOT_HPP
#define DRIVEROBOT_HPP
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/float32.hpp"
#include "geometry_msgs/msg/twist.hpp"

using std::placeholders::_1;

class DriveRobot : public rclcpp::Node
{
public:
  DriveRobot();
  float ParseMsg(float msg);

private:
  void topic_callback(const std_msgs::msg::Float32::SharedPtr msg);
  rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr subscription_;
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;

};

#endif //DRIVEROBOT_HPP

driverobot_test.cpp

#include "driverobot.hpp"
#include "gtest/gtest.h"

TEST(DriveRobot_test, parse_msg_test)
{
    DriveRobot robot;
    EXPECT_FLOAT_EQ(0.22, robot.ParseMsg(12));
    EXPECT_FLOAT_EQ(-0.22, robot.ParseMsg(-1));
    EXPECT_FLOAT_EQ(0.14, robot.ParseMsg(0.14));
    EXPECT_EQ(0, robot.ParseMsg(0));
}
TEST(Driverobot_test, deliberate_fail)
{
    DriveRobot robot;
    EXPECT_EQ(0, robot.ParseMsg(1));
}

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    ::testing::InitGoogleTest(&argc, argv);
    return RUN_ALL_TESTS();
}

CMakeLists.txt

cmake_minimum_required(VERSION 3.16.3)
project(driverobot)

set(THIS_PACKAGE_INCLUDE_DEPENDS
    rclcpp
    std_msgs
    geometry_msgs
)

find_package(ament_cmake REQUIRED)

foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
  find_package(${Dependency} REQUIRED)
endforeach()

if(BUILD_TESTING)
  find_package(ament_cmake_gtest REQUIRED)
  find_package(ament_lint_auto REQUIRED)

  # the following lines skip linters
  set(ament_cmake_cppcheck_FOUND TRUE)
  set(ament_cmake_copyright_FOUND TRUE)
  set(ament_cmake_cpplint_FOUND TRUE)
  set(ament_cmake_flake8_FOUND TRUE)
  set(ament_cmake_uncrustify_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()

  # Run all lint tests in package.xml except those listed above
  ament_lint_auto_find_test_dependencies()
  ament_add_gtest_executable(driverobot_test
    test/driverobot_test.cpp
  )

  target_include_directories(driverobot_test
  PUBLIC
    $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
    $<INSTALL_INTERFACE:include>)

  target_sources(${PROJECT_NAME}_test PRIVATE src/driverobot.cpp)
  # add_executable(${PROJECT_NAME}_test ${target_sources})# make the tests an executable so you can manually run them if needed
  ament_target_dependencies(${PROJECT_NAME}_test ${THIS_PACKAGE_INCLUDE_DEPENDS})

  install(TARGETS
  ${PROJECT_NAME}_test
      DESTINATION test/${PROJECT_NAME})

endif()

ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2022-04-22 13:21:47 -0500

aprotyas gravatar image

updated 2022-04-22 13:29:46 -0500

ament_add_gtest_executableonly calls add_executable() and links the target against the gtest libraries. It does not register the executable as a test. (Check https://github.com/ament/ament_cmake/...)

What you want instead is ament_add_gtest. This macro calls add_executable(), links the target against the gtest libraries, and registers the executable as a test. (Check https://github.com/ament/ament_cmake/...)


For completeness, if you were using ament_add_gtest_executable, you would have to supplement it with a call to ament_add_gtest_test, which registers an executable created with ament_add_gtest_executableas a test. (Check https://github.com/ament/ament_cmake/...)

So you either do:

ament_add_gtest(driverobot_test
    test/driverobot_test.cpp
)

or

ament_add_gtest_executable(driverobot_test
    test/driverobot_test.cpp
)
ament_add_gtest_test(driverobot_test)
edit flag offensive delete link more

Comments

1

I just lost 2 hours of my life because of this. How did you learn about this?

psammut gravatar image psammut  ( 2022-06-28 18:41:46 -0500 )edit
2

I want to say "I was there when it was written", but really I also wasted a couple of hours and was frustrated enough to go through the ament_cmake code haha!

aprotyas gravatar image aprotyas  ( 2022-06-28 19:55:28 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-04-22 04:06:37 -0500

Seen: 923 times

Last updated: Apr 22 '22