Skip to content

Commit

Permalink
Add tests for hasError() method
Browse files Browse the repository at this point in the history
  • Loading branch information
bochen87 committed Oct 4, 2018
1 parent 73b4483 commit 1ea0662
Show file tree
Hide file tree
Showing 6 changed files with 129 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
///////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2015, Shadow Robot Company Ltd.
//
// 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 hiDOF, 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.
//////////////////////////////////////////////////////////////////////////////



#ifndef CONTROLLER_MANAGER_TESTS_MY_ROBOT_HW_5_H
#define CONTROLLER_MANAGER_TESTS_MY_ROBOT_HW_5_H

#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/robot_hw.h>
#include <pluginlib/class_list_macros.hpp>

namespace combined_robot_hw_tests
{

class MyRobotHW5 : public hardware_interface::RobotHW
{
public:
MyRobotHW5();
virtual ~MyRobotHW5(){};
virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh);
void read(const ros::Time& time, const ros::Duration& period);
void write(const ros::Time& time, const ros::Duration& period);
bool hasError();

};
}


#endif
61 changes: 61 additions & 0 deletions combined_robot_hw_tests/src/my_robot_hw_5.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
///////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2015, Shadow Robot Company Ltd.
//
// 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 Shadow Robot Company Ltd. 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.
//////////////////////////////////////////////////////////////////////////////


#include <combined_robot_hw_tests/my_robot_hw_5.h>

namespace combined_robot_hw_tests
{

MyRobotHW5::MyRobotHW5()
{
}

bool MyRobotHW5::init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh)
{
return true;
}


void MyRobotHW5::read(const ros::Time& time, const ros::Duration& period)
{

}

void MyRobotHW5::write(const ros::Time& time, const ros::Duration& period)
{
}

bool MyRobotHW5::hasError()
{
return true;
}

}

PLUGINLIB_EXPORT_CLASS( combined_robot_hw_tests::MyRobotHW5, hardware_interface::RobotHW)

2 changes: 2 additions & 0 deletions combined_robot_hw_tests/test/cm_test.test
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
joint_name_filter: right_arm
my_robot_hw_4:
type: combined_robot_hw_tests/MyRobotHW4
my_robot_hw_5:
type: combined_robot_hw_tests/MyRobotHW5
my_controller:
type: controller_manager_tests/EffortTestController
my_controller2:
Expand Down
3 changes: 3 additions & 0 deletions combined_robot_hw_tests/test/combined_robot_hw_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,9 @@ TEST(CombinedRobotHWTests, combinationOk)
robot_hw.write(ros::Time::now(), period);
ej_handle = ej_interface->getHandle("test_joint2");
ASSERT_FLOAT_EQ(3.5, ej_handle.getCommand());

bool error = robot_hw.hasError();
ASSERT_TRUE(error);
}

TEST(CombinedRobotHWTests, switchOk)
Expand Down
3 changes: 3 additions & 0 deletions combined_robot_hw_tests/test/combined_robot_hw_test.test
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
- my_robot_hw_2
- my_robot_hw_3
- my_robot_hw_4
- my_robot_hw_5
my_robot_hw_1:
type: combined_robot_hw_tests/MyRobotHW1
my_robot_hw_2:
Expand All @@ -18,6 +19,8 @@
joint_name_filter: right_arm
my_robot_hw_4:
type: combined_robot_hw_tests/MyRobotHW4
my_robot_hw_5:
type: combined_robot_hw_tests/MyRobotHW5
</rosparam>

<test test-name="combined_robot_hw_tests" pkg="combined_robot_hw_tests" type="combined_robot_hw_test"/>
Expand Down
6 changes: 6 additions & 0 deletions combined_robot_hw_tests/test_robot_hw_plugin.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,4 +22,10 @@
A type of RobotHW
</description>
</class>

<class name="combined_robot_hw_tests/MyRobotHW5" type="combined_robot_hw_tests::MyRobotHW5" base_class_type="hardware_interface::RobotHW">
<description>
A type of RobotHW
</description>
</class>
</library>

0 comments on commit 1ea0662

Please sign in to comment.