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

Python rostest succeeds and fails

asked 2017-11-15 05:28:14 -0500

ramasri gravatar image

updated 2017-11-15 09:01:01 -0500

gvdhoorn gravatar image

When i run the unit test using rostest command it fails, when I run it using rosrun it always succeeds.

ROSRUN: ALWAYS SUCCEEDS

I am trying to create simple unit test that does nothing, it always returns the following :

SUMMARY:
 * RESULT: SUCCESS
 * TESTS: 0
 * ERRORS: 0 []
 * FAILURES: 0 []

Output of test results is

<?xml version="1.0" encoding="utf-8"?>
<testsuite errors="0" failures="0" name="unittest.suite.TestSuite" tests="0" time="0.000">
  <system-out><![CDATA[]]></system-out>
  <system-err><![CDATA[]]></system-err>
</testsuite>

I run it using rosrun package-name python-test-exec

this is my unit test file

#!/usr/bin/env python
from __future__ import print_function
PKG = 'sample_ros_py'
NAME = 'test_topic'
import sys
import unittest
from std_msgs.msg import String

import rospy
import rostest
import time

class test_topic(unittest.TestCase):

def __init__(self, *args):
    self.success = False

def is_talker_up(self):
    self.assertEquals(1,2)

def trial_2(self):
     self.assertEquals(2,2)

if __name__ == '__main__':
rostest.rosrun(PKG, NAME, test_topic, sys.argv)

this is the cmake file :

  if(CATKIN_ENABLE_TESTING)
   find_package(rostest REQUIRED)
   add_rostest(test/sample_ros_py.test)
   endif()

Whatever I change in the python test file I always get the result.

ROSTEST : ALWAYS FAILING

Additionally I have a rostest file:

<?xml version="1.0" encoding="UTF-8"?>
<launch>
    <node name="talker" pkg="sample_ros_py" type="talker" output="screen" />
    <test test-name="test_topic_test" pkg="sample_ros_py" type="test_topic" name="test_topic"/>
</launch>

Which does not run at all!

I get :

[ROSUNIT] Outputting test results to /home/rama/.ros/test_results/sample_ros_py/rostest-test_sample_ros_py.xml
testtest_topic_test ... FAILURE!
FAILURE: Test node [sample_ros_py/test_topic] does not exist or is not executable
  File "/usr/lib/python2.7/unittest/case.py", line 331, in run
    testMethod()
  File "/opt/ros/indigo/lib/python2.7/dist-packages/rostest/runner.py", line 93, in fn
    self.fail(message)
  File "/usr/lib/python2.7/unittest/case.py", line 412, in fail
    raise self.failureException(msg)
--------------------------------------------------------------------------------

[ROSTEST]-----------------------------------------------------------------------

[testtest_topic_test][failed]

SUMMARY
 * RESULT: FAIL
 * TESTS: 0
 * ERRORS: 0
 * FAILURES: 1

ERROR: The following tests failed to run:
 * testtest_topic_test

Why does is succeed in one and fail in the other?

this is the log file content :

[rostest][INFO] 2017-11-15 12:16:07,447: rostest starting with options {'text_mode': False, 'pkg_dir': None, 'results_base_dir': None, 'package': None, 'clear': None, 'reuse_master': None, 'results_filename': None}, args ['/home/rama/catkin_ws/src/sample_ros_py/test/sample_ros_py.test']
[roslaunch][INFO] 2017-11-15 12:16:07,466: loading roscore config file /opt/ros/indigo/etc/ros/roscore.xml
[roslaunch][INFO] 2017-11-15 12:16:07,565: Added core node of type [rosout/rosout] in namespace [/]
[roslaunch.config][INFO] 2017-11-15 12:16:07,566: loading config file /home/catkin_ws/src/sample_ros_py/test/sample_ros_py.test
[roslaunch][INFO] 2017-11-15 12:16:07,568: Added node of type [sample_ros_py/talker] in namespace [/]
[roslaunch][INFO] 2017-11-15 12:16:07,568: ... selected machine [] for node of type [sample_ros_py/talker]
[roslaunch][INFO] 2017-11-15 12:16:07,568: ... selected machine [] for node of type [sample_ros_py/test_topic]
[rostest][INFO] 2017-11-15 12:16:07,597: setup[/home/rama/catkin_ws/src/sample_ros_py/test/sample_ros_py.test] run_id[607c2bd0-c9f6-11e7-b23e-7824af3a7c31] starting
[roslaunch.pmon][INFO] 2017-11-15 12:16:07,598: start_process_monitor: creating ProcessMonitor
[roslaunch.pmon][INFO ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2017-11-15 09:02:19 -0500

gvdhoorn gravatar image

updated 2017-11-15 09:03:13 -0500

I am trying to create simple unit test that does nothing, it always returns the following :

SUMMARY: * RESULT: SUCCESS * TESTS: 0 * ERRORS: 0 [] * FAILURES: 0 []

Output of test results is

<testsuite errors="0" failures="0" name="unittest.suite.TestSuite" tests="0" time="0.000">

Are you sure your test is being run? I see TESTS: 0 and also in the xml output: tests="0".

No tests -> always succeed.

ROSTEST : ALWAYS FAILING

<node name="talker" pkg="sample_ros_py" type="talker" output="screen" />

Here it is actually trying to run your test, but if this is a Python script the <node .. type="" .. /> line should probably include the extension.

The error message seems to suggest that rostest can't find your script because of that:

FAILURE: Test node [sample_ros_py/test_topic] does not exist or is not executable

Can you check the name and extension of the Python file?

edit flag offensive delete link more

Question Tools

Stats

Asked: 2017-11-15 05:28:14 -0500

Seen: 1,255 times

Last updated: Nov 15 '17