Skip to content

Commit 465039f

Browse files
committed
Add tests for hasError() method
1 parent 73b4483 commit 465039f

File tree

6 files changed

+129
-0
lines changed

6 files changed

+129
-0
lines changed
Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,54 @@
1+
///////////////////////////////////////////////////////////////////////////////
2+
// Copyright (C) 2015, Shadow Robot Company Ltd.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
// * Redistributions of source code must retain the above copyright notice,
7+
// this list of conditions and the following disclaimer.
8+
// * Redistributions in binary form must reproduce the above copyright
9+
// notice, this list of conditions and the following disclaimer in the
10+
// documentation and/or other materials provided with the distribution.
11+
// * Neither the name of hiDOF, Inc. nor the names of its
12+
// contributors may be used to endorse or promote products derived from
13+
// this software without specific prior written permission.
14+
//
15+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25+
// POSSIBILITY OF SUCH DAMAGE.
26+
//////////////////////////////////////////////////////////////////////////////
27+
28+
29+
30+
#ifndef CONTROLLER_MANAGER_TESTS_MY_ROBOT_HW_5_H
31+
#define CONTROLLER_MANAGER_TESTS_MY_ROBOT_HW_5_H
32+
33+
#include <hardware_interface/joint_command_interface.h>
34+
#include <hardware_interface/robot_hw.h>
35+
#include <pluginlib/class_list_macros.hpp>
36+
37+
namespace combined_robot_hw_tests
38+
{
39+
40+
class MyRobotHW5 : public hardware_interface::RobotHW
41+
{
42+
public:
43+
MyRobotHW5();
44+
virtual ~MyRobotHW5(){};
45+
virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh);
46+
void read(const ros::Time& time, const ros::Duration& period);
47+
void write(const ros::Time& time, const ros::Duration& period);
48+
bool hasError();
49+
50+
};
51+
}
52+
53+
54+
#endif
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
///////////////////////////////////////////////////////////////////////////////
2+
// Copyright (C) 2015, Shadow Robot Company Ltd.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
// * Redistributions of source code must retain the above copyright notice,
7+
// this list of conditions and the following disclaimer.
8+
// * Redistributions in binary form must reproduce the above copyright
9+
// notice, this list of conditions and the following disclaimer in the
10+
// documentation and/or other materials provided with the distribution.
11+
// * Neither the name of Shadow Robot Company Ltd. nor the names of its
12+
// contributors may be used to endorse or promote products derived from
13+
// this software without specific prior written permission.
14+
//
15+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25+
// POSSIBILITY OF SUCH DAMAGE.
26+
//////////////////////////////////////////////////////////////////////////////
27+
28+
29+
#include <combined_robot_hw_tests/my_robot_hw_5.h>
30+
31+
namespace combined_robot_hw_tests
32+
{
33+
34+
MyRobotHW3::MyRobotHW5()
35+
{
36+
}
37+
38+
bool MyRobotHW5::init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh)
39+
{
40+
return true;
41+
}
42+
43+
44+
void MyRobotHW5::read(const ros::Time& time, const ros::Duration& period)
45+
{
46+
47+
}
48+
49+
void MyRobotHW5::write(const ros::Time& time, const ros::Duration& period)
50+
{
51+
}
52+
53+
bool MyRobotHW5::hasError()
54+
{
55+
return true;
56+
}
57+
58+
}
59+
60+
PLUGINLIB_EXPORT_CLASS( combined_robot_hw_tests::MyRobotHW5, hardware_interface::RobotHW)
61+

combined_robot_hw_tests/test/cm_test.test

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
joint_name_filter: right_arm
2121
my_robot_hw_4:
2222
type: combined_robot_hw_tests/MyRobotHW4
23+
my_robot_hw_5:
24+
type: combined_robot_hw_tests/MyRobotHW5
2325
my_controller:
2426
type: controller_manager_tests/EffortTestController
2527
my_controller2:

combined_robot_hw_tests/test/combined_robot_hw_test.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,9 @@ TEST(CombinedRobotHWTests, combinationOk)
9494
robot_hw.write(ros::Time::now(), period);
9595
ej_handle = ej_interface->getHandle("test_joint2");
9696
ASSERT_FLOAT_EQ(3.5, ej_handle.getCommand());
97+
98+
bool error = robot_hw.hasError();
99+
ASSERT_TRUE(error);
97100
}
98101

99102
TEST(CombinedRobotHWTests, switchOk)

combined_robot_hw_tests/test/combined_robot_hw_test.test

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
- my_robot_hw_2
66
- my_robot_hw_3
77
- my_robot_hw_4
8+
- my_robot_hw_5
89
my_robot_hw_1:
910
type: combined_robot_hw_tests/MyRobotHW1
1011
my_robot_hw_2:
@@ -18,6 +19,8 @@
1819
joint_name_filter: right_arm
1920
my_robot_hw_4:
2021
type: combined_robot_hw_tests/MyRobotHW4
22+
my_robot_hw_5:
23+
type: combined_robot_hw_tests/MyRobotHW5
2124
</rosparam>
2225

2326
<test test-name="combined_robot_hw_tests" pkg="combined_robot_hw_tests" type="combined_robot_hw_test"/>

combined_robot_hw_tests/test_robot_hw_plugin.xml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,4 +22,10 @@
2222
A type of RobotHW
2323
</description>
2424
</class>
25+
26+
<class name="combined_robot_hw_tests/MyRobotHW5" type="combined_robot_hw_tests::MyRobotHW5" base_class_type="hardware_interface::RobotHW">
27+
<description>
28+
A type of RobotHW
29+
</description>
30+
</class>
2531
</library>

0 commit comments

Comments
 (0)