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
100 lines
4.4 KiB
XML
100 lines
4.4 KiB
XML
<?xml version="1.0"?>
|
||
<!--
|
||
Copyright 2025 Reazon Holdings, Inc.
|
||
|
||
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.
|
||
-->
|
||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||
<xacro:macro name="openarm_ros2_control" params="name initial_positions_file prefix:='' can_device='can0'">
|
||
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
|
||
|
||
<ros2_control name="${prefix}${name}" 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>
|
||
<param name="prefix">${prefix}</param>
|
||
<param name="can_device">${can_device}</param>
|
||
</hardware>
|
||
<joint name="${prefix}rev1">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}rev2">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}rev3">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}rev4">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}rev5">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}rev6">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}rev7">
|
||
<command_interface name="position"/>
|
||
<command_interface name="velocity"/>
|
||
<command_interface name="effort"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
<state_interface name="effort"/>
|
||
</joint>
|
||
<joint name="${prefix}left_pris1">
|
||
<command_interface name="position"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
</joint>
|
||
|
||
<!-- <joint name="${prefix}right_pris2">
|
||
<state_interface name="position">
|
||
<param name="initial_value">${initial_positions['right_pris2']}</param>
|
||
</state_interface>
|
||
</joint> -->
|
||
|
||
</ros2_control>
|
||
</xacro:macro>
|
||
</robot>
|