openarm_ros2/openarm_hardware/test/test_openarm_hardware.cpp
takuya kodama 56f98bd226
Relicense to Apache License 2.0 from BSD 3-Clause License (#13)
We are standardizing our software under Apache License 2.0. This PR
replaces existing BSD 3-Clause License with Apache 2.0 in this
repository.

## About Copyright

All commits in this repository are made by Reazon Holdings, Inc.
members, so the copyright has been added as follows.
- `Copyright 2025 Reazon Holdings, Inc.`
```console
$ git shortlog -sn
    55	Thomason Zhou
    14	thomason
     5	takuya kodama
     1	Fujimoto Seiji
     1	edwin-giang
     1	toki
```

## How it was done

We added the new license header directory by directory, with each commit
covering a single directory to make review easier.
To ensure there are no missing files, we ran the following commands.

```
$ grep -RIL --exclude-dir='.git' --exclude='*.stl' "Apache License, Version 2.0" .
./openarm_bringup/README.md
./openarm_bimanual_moveit_config/README.md
./openarm_bimanual_description/urdf/openarm_bimanual.urdf
./.gitignore
./README.md
./openarm_description/urdf/openarm.urdf
./openarm_description/resource/openarm_description
```

The following files are auto-generated. 
- openarm_bimanual_description/urdf/openarm_bimanual.urdf
- openarm_description/urdf/openarm.urdf
2025-05-22 16:22:55 +09:00

129 lines
4.9 KiB
C++

// Copyright 2025 Reazon Holdings, Inc.
// Copyright 2025 Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gmock/gmock.h>
#include <string>
#include "hardware_interface/resource_manager.hpp"
#include "ros2_control_test_assets/components_urdfs.hpp"
#include "ros2_control_test_assets/descriptions.hpp"
class TestOpenArmHW : public ::testing::Test {
protected:
void SetUp() override {
openarm_hardware_7dof_ =
R"(
<ros2_control name="OpenArmHW7DOF" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
<plugin>openarm_hardware/OpenArmHW</plugin>
</hardware>
<joint name="rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_pris1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_pris2">
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
</joint>
</ros2_control>
)";
}
std::string openarm_hardware_7dof_;
};
TEST_F(TestOpenArmHW, load_openarm_hardware_7dof) {
auto urdf = ros2_control_test_assets::urdf_head + openarm_hardware_7dof_ +
ros2_control_test_assets::urdf_tail;
ASSERT_NO_THROW(hardware_interface::ResourceManager rm(urdf));
}