Add mujoco ros2 control (#26)

Add support for simulated openarm hardware with MuJoCo backend.
This commit is contained in:
thomason 2025-07-03 21:43:08 -07:00 committed by GitHub
parent d151836956
commit 158d15dfa9
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
53 changed files with 1627 additions and 698 deletions

0
.docker/COLCON_IGNORE Normal file
View File

14
.docker/Dockerfile Normal file
View File

@ -0,0 +1,14 @@
FROM ghcr.io/reazon-research/ros2:humble
COPY ros_entrypoint.sh /ros_entrypoint.sh
RUN . /opt/ros/humble/setup.sh && \
apt update && \
apt install nlohmann-json3-dev -y && \
mkdir --parents ~/ros2_ws/src && \
git clone --branch main https://github.com/reazon-research/openarm_ros2.git ~/ros2_ws/src/openarm_ros2 && \
cd ~/ros2_ws && \
rosdep install --from-paths src --ignore-src -r -y && \
colcon build --symlink-install && \
chmod +x /ros_entrypoint.sh
ENTRYPOINT [ "/ros_entrypoint.sh" ]

27
.docker/README.md Normal file
View File

@ -0,0 +1,27 @@
# Docker GUI Forwarding
On Linux:
```sh
host +local:root
```
```sh
docker run --env DISPLAY=$DISPLAY \
--volume /tmp/.X11-unix:/tmp/.X11-unix \
--network=host \
-it ghcr.io/reazon-research/openarm:v0.3 \
/bin/bash
```
Open the MuJoCo sim at
[https://thomasonzhou.github.io/mujoco_anywhere/](https://thomasonzhou.github.io/mujoco_anywhere/)
```sh
. ~/ros2_ws/install/setup.bash && \
ros2 launch -d openarm_bimanual_moveit_config demo.launch.py hardware_type:=sim
```
# To build the latest image (v0.3)
```sh
docker build --no-cache -t ghcr.io/reazon-research/openarm:v0.3 .
```

View File

@ -0,0 +1,7 @@
#!/bin/bash
set -e
source /opt/ros/humble/setup.sh
source ~/ros2_ws/install/setup.bash
exec "$@"

View File

@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and # See the License for the specific language governing permissions and
# limitations under the License. # limitations under the License.
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.22)
project(openarm) project(openarm)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")

View File

@ -30,6 +30,7 @@
<exec_depend>openarm_bringup</exec_depend> <exec_depend>openarm_bringup</exec_depend>
<exec_depend>openarm_description</exec_depend> <exec_depend>openarm_description</exec_depend>
<exec_depend>openarm_hardware</exec_depend> <exec_depend>openarm_hardware</exec_depend>
<exec_depend>openarm_mujoco_hardware</exec_depend>
<test_depend>ament_lint_auto</test_depend> <test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend> <test_depend>ament_lint_common</test_depend>

View File

@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and # See the License for the specific language governing permissions and
# limitations under the License. # limitations under the License.
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.22)
project(openarm_bimanual_bringup) project(openarm_bimanual_bringup)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")

View File

@ -22,9 +22,11 @@ def generate_launch_description():
realsense_share_dir = FindPackageShare("realsense2_camera") realsense_share_dir = FindPackageShare("realsense2_camera")
rs_launch_path = [realsense_share_dir, "/launch/rs_launch.py"] rs_launch_path = [realsense_share_dir, "/launch/rs_launch.py"]
return LaunchDescription([ return LaunchDescription(
[
IncludeLaunchDescription( IncludeLaunchDescription(
PythonLaunchDescriptionSource(rs_launch_path), PythonLaunchDescriptionSource(rs_launch_path),
launch_arguments={"pointcloud.enable": "true"}.items() launch_arguments={"pointcloud.enable": "true"}.items(),
)
]
) )
])

View File

@ -38,7 +38,8 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time") use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument( use_sim_time_launch_arg = DeclareLaunchArgument(
name="use_sim_time", default_value="false") name="use_sim_time", default_value="false"
)
robot_state_publisher_node = IncludeLaunchDescription( robot_state_publisher_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource( PythonLaunchDescriptionSource(
@ -63,8 +64,11 @@ def generate_launch_description():
} }
controller_params = PathJoinSubstitution( controller_params = PathJoinSubstitution(
[FindPackageShare(package="openarm_bimanual_bringup"), [
"config", "controllers.yaml"] FindPackageShare(package="openarm_bimanual_bringup"),
"config",
"controllers.yaml",
]
) )
controller_manager = Node( controller_manager = Node(

View File

@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and # See the License for the specific language governing permissions and
# limitations under the License. # limitations under the License.
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.22)
project(openarm_bimanual_description) project(openarm_bimanual_description)
find_package(ament_cmake REQUIRED) find_package(ament_cmake REQUIRED)

View File

@ -25,15 +25,16 @@ from launch_ros.parameter_descriptions import ParameterValue
def generate_launch_description(): def generate_launch_description():
pkg_share = Path( pkg_share = Path(
launch_ros.substitutions.FindPackageShare(package="openarm_bimanual_description").find( launch_ros.substitutions.FindPackageShare(
"openarm_bimanual_description" package="openarm_bimanual_description"
) ).find("openarm_bimanual_description")
) )
default_model_path = pkg_share / "urdf/openarm_bimanual.urdf.xacro" default_model_path = pkg_share / "urdf/openarm_bimanual.urdf.xacro"
use_sim_time = LaunchConfiguration("use_sim_time") use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument( use_sim_time_launch_arg = DeclareLaunchArgument(
"use_sim_time", default_value="true") "use_sim_time", default_value="true"
)
robot_state_publisher_node = launch_ros.actions.Node( robot_state_publisher_node = launch_ros.actions.Node(
package="robot_state_publisher", package="robot_state_publisher",

View File

@ -25,9 +25,9 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description(): def generate_launch_description():
pkg_share = Path( pkg_share = Path(
launch_ros.substitutions.FindPackageShare(package="openarm_bimanual_description").find( launch_ros.substitutions.FindPackageShare(
"openarm_bimanual_description" package="openarm_bimanual_description"
) ).find("openarm_bimanual_description")
) )
default_model_path = pkg_share / "urdf/openarm_bimanual.urdf.xacro" default_model_path = pkg_share / "urdf/openarm_bimanual.urdf.xacro"
default_rviz_config_path = pkg_share / "rviz/robot_description.rviz" default_rviz_config_path = pkg_share / "rviz/robot_description.rviz"

View File

@ -37,7 +37,8 @@ def generate_launch_description():
# Make path to resources dir without last package_name fragment. # Make path to resources dir without last package_name fragment.
path_to_share_dir_clipped = "".join( path_to_share_dir_clipped = "".join(
get_package_share_directory(resources_package).rsplit( get_package_share_directory(resources_package).rsplit(
"/" + resources_package, 1) "/" + resources_package, 1
)
) )
# Gazebo hint for resources. # Gazebo hint for resources.
@ -57,10 +58,12 @@ def generate_launch_description():
use_custom_world = LaunchConfiguration("use_custom_world") use_custom_world = LaunchConfiguration("use_custom_world")
use_custom_world_launch_arg = DeclareLaunchArgument( use_custom_world_launch_arg = DeclareLaunchArgument(
"use_custom_world", default_value="true") "use_custom_world", default_value="true"
)
gazebo_world = LaunchConfiguration("gazebo_world") gazebo_world = LaunchConfiguration("gazebo_world")
gazebo_world_launch_arg = DeclareLaunchArgument( gazebo_world_launch_arg = DeclareLaunchArgument(
"gazebo_world", default_value="empty.sdf") "gazebo_world", default_value="empty.sdf"
)
# prepare custom world # prepare custom world
world = os.getenv("GZ_SIM_WORLD", "empty") world = os.getenv("GZ_SIM_WORLD", "empty")
@ -78,9 +81,11 @@ def generate_launch_description():
PythonLaunchDescriptionSource( PythonLaunchDescriptionSource(
os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py"), os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py"),
), ),
launch_arguments=launch_arguments launch_arguments=(
launch_arguments
if use_custom_world if use_custom_world
else dict(gz_args="-r " + gazebo_world + " --verbose").items(), else dict(gz_args="-r " + gazebo_world + " --verbose").items()
),
) )
# Spawn # Spawn
@ -104,7 +109,8 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time") use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument( use_sim_time_launch_arg = DeclareLaunchArgument(
"use_sim_time", default_value="true") "use_sim_time", default_value="true"
)
use_rviz = LaunchConfiguration("use_rviz") use_rviz = LaunchConfiguration("use_rviz")
use_rviz_arg = DeclareLaunchArgument("use_rviz", default_value="true") use_rviz_arg = DeclareLaunchArgument("use_rviz", default_value="true")

View File

@ -1,6 +1,6 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from openarm_bimanual_description/urdf/openarm_bimanual.urdf.xacro | --> <!-- | This document was autogenerated by xacro from openarm_bimanual.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- <!--
@ -171,6 +171,7 @@
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<!-- ros2_control configuration is handled separately in openarm.urdf.xacro -->
<link name="right_dummy_link"/> <link name="right_dummy_link"/>
<joint name="right_dummy_joint" type="fixed"> <joint name="right_dummy_joint" type="fixed">
<parent link="right_dummy_link"/> <parent link="right_dummy_link"/>
@ -426,20 +427,21 @@
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.9599310885968811" upper="0.9599310885968811" velocity="0.0"/> <limit effort="0.0" lower="-0.9599310885968811" upper="0.9599310885968811" velocity="0.0"/>
</joint> </joint>
<joint name="right_left_pris1" type="prismatic"> <!-- this is used as the actuator interface, the other gripper mimics motion -->
<joint name="right_gripper" type="prismatic">
<parent link="right_link8"/> <parent link="right_link8"/>
<child link="right_link_left_jaw"/> <child link="right_link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/> <origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint> </joint>
<joint name="right_right_pris2" type="prismatic"> <joint name="right_gripper_mimic" type="prismatic">
<parent link="right_link8"/> <parent link="right_link8"/>
<child link="right_link_right_jaw"/> <child link="right_link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/> <origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="right_left_pris1" multiplier="-1.0" offset="0.0"/> <mimic joint="right_gripper" multiplier="-1.0" offset="0.0"/>
</joint> </joint>
<joint name="right_virtual_gripper_center" type="fixed"> <joint name="right_virtual_gripper_center" type="fixed">
<parent link="right_link8"/> <parent link="right_link8"/>
@ -454,6 +456,7 @@
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<!-- ros2_control configuration is handled separately in openarm.urdf.xacro -->
<link name="left_dummy_link"/> <link name="left_dummy_link"/>
<joint name="left_dummy_joint" type="fixed"> <joint name="left_dummy_joint" type="fixed">
<parent link="left_dummy_link"/> <parent link="left_dummy_link"/>
@ -709,20 +712,21 @@
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.9599310885968811" upper="0.9599310885968811" velocity="0.0"/> <limit effort="0.0" lower="-0.9599310885968811" upper="0.9599310885968811" velocity="0.0"/>
</joint> </joint>
<joint name="left_left_pris1" type="prismatic"> <!-- this is used as the actuator interface, the other gripper mimics motion -->
<joint name="left_gripper" type="prismatic">
<parent link="left_link8"/> <parent link="left_link8"/>
<child link="left_link_left_jaw"/> <child link="left_link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/> <origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint> </joint>
<joint name="left_right_pris2" type="prismatic"> <joint name="left_gripper_mimic" type="prismatic">
<parent link="left_link8"/> <parent link="left_link8"/>
<child link="left_link_right_jaw"/> <child link="left_link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/> <origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="left_left_pris1" multiplier="-1.0" offset="0.0"/> <mimic joint="left_gripper" multiplier="-1.0" offset="0.0"/>
</joint> </joint>
<joint name="left_virtual_gripper_center" type="fixed"> <joint name="left_virtual_gripper_center" type="fixed">
<parent link="left_link8"/> <parent link="left_link8"/>
@ -743,64 +747,69 @@
<joint name="right_rev1"> <joint name="right_rev1">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_rev2"> <joint name="right_rev2">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_rev3"> <joint name="right_rev3">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_rev4"> <joint name="right_rev4">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_rev5"> <joint name="right_rev5">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_rev6"> <joint name="right_rev6">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_rev7"> <joint name="right_rev7">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="right_left_pris1"> <joint name="right_gripper">
<command_interface name="position"/> <command_interface name="position"/>
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
</joint> </joint>
<!-- <joint name="${prefix}gripper_mimic">
<state_interface name="position">
<param name="initial_value">${initial_positions['gripper_mimic']}</param>
</state_interface>
</joint> -->
</ros2_control> </ros2_control>
<ros2_control name="left_LeftOpenArmHW" type="system"> <ros2_control name="left_LeftOpenArmHW" type="system">
<hardware> <hardware>
@ -811,63 +820,68 @@
<joint name="left_rev1"> <joint name="left_rev1">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_rev2"> <joint name="left_rev2">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_rev3"> <joint name="left_rev3">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_rev4"> <joint name="left_rev4">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_rev5"> <joint name="left_rev5">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_rev6"> <joint name="left_rev6">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_rev7"> <joint name="left_rev7">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_left_pris1"> <joint name="left_gripper">
<command_interface name="position"/> <command_interface name="position"/>
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
</joint> </joint>
<!-- <joint name="${prefix}gripper_mimic">
<state_interface name="position">
<param name="initial_value">${initial_positions['gripper_mimic']}</param>
</state_interface>
</joint> -->
</ros2_control> </ros2_control>
</robot> </robot>

View File

@ -15,6 +15,7 @@
 limitations under the License.  limitations under the License.
--> -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:arg name="hardware_type" default="real" />
<!-- Robot description parameters --> <!-- Robot description parameters -->
<xacro:arg name="prefix" default="" /> <xacro:arg name="prefix" default="" />
@ -22,7 +23,7 @@
<!-- Control-related parameters --> <!-- Control-related parameters -->
<xacro:arg name="right_can_device" default="can0" /> <xacro:arg name="right_can_device" default="can0" />
<xacro:arg name="left_can_device" default="can1" /> <xacro:arg name="left_can_device" default="can1" />
<xacro:arg name="use_mock_hardware" default="false" /> <xacro:arg name="hardware_type" default="real" />
<xacro:arg name="mock_sensor_commands" default="false" /> <xacro:arg name="mock_sensor_commands" default="false" />
<xacro:include filename="$(find openarm_description)/urdf/openarm.robot.xacro"/> <xacro:include filename="$(find openarm_description)/urdf/openarm.robot.xacro"/>
@ -55,7 +56,7 @@
<xacro:arg name="right_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" /> <xacro:arg name="right_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:arg name="left_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" /> <xacro:arg name="left_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="RightOpenArmHW" prefix="right_" initial_positions_file="$(arg right_initial_positions_file)" can_device="$(arg right_can_device)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/> <xacro:openarm_ros2_control name="RightOpenArmHW" prefix="right_" initial_positions_file="$(arg right_initial_positions_file)" can_device="$(arg right_can_device)" hardware_type="$(arg hardware_type)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
<xacro:openarm_ros2_control name="LeftOpenArmHW" prefix="left_" initial_positions_file="$(arg left_initial_positions_file)" can_device="$(arg left_can_device)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/> <xacro:openarm_ros2_control name="LeftOpenArmHW" prefix="left_" initial_positions_file="$(arg left_initial_positions_file)" can_device="$(arg left_can_device)" hardware_type="$(arg hardware_type)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
</robot> </robot>

View File

@ -15,7 +15,7 @@
# Default initial positions for openarm_bimanual's ros2_control fake system # Default initial positions for openarm_bimanual's ros2_control fake system
initial_positions: initial_positions:
left_left_pris1: 0 left_gripper: 0
left_rev1: 0 left_rev1: 0
left_rev2: 0 left_rev2: 0
left_rev3: 0 left_rev3: 0
@ -23,7 +23,7 @@ initial_positions:
left_rev5: 0 left_rev5: 0
left_rev6: 0 left_rev6: 0
left_rev7: 0 left_rev7: 0
right_left_pris1: 0 right_gripper: 0
right_rev1: 0 right_rev1: 0
right_rev2: 0 right_rev2: 0
right_rev3: 0 right_rev3: 0

View File

@ -22,7 +22,7 @@ default_acceleration_scaling_factor: 0.1
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits: joint_limits:
left_left_pris1: left_gripper:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.10000000000000001 max_velocity: 0.10000000000000001
has_acceleration_limits: false has_acceleration_limits: false
@ -62,7 +62,7 @@ joint_limits:
max_velocity: 0 max_velocity: 0
has_acceleration_limits: false has_acceleration_limits: false
max_acceleration: 0 max_acceleration: 0
right_left_pris1: right_gripper:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.10000000000000001 max_velocity: 0.10000000000000001
has_acceleration_limits: false has_acceleration_limits: false

View File

@ -50,12 +50,12 @@ moveit_simple_controller_manager:
left_gripper_controller: left_gripper_controller:
type: GripperCommand type: GripperCommand
joints: joints:
- left_left_pris1 - left_gripper
action_ns: gripper_cmd action_ns: gripper_cmd
default: true default: true
right_gripper_controller: right_gripper_controller:
type: GripperCommand type: GripperCommand
joints: joints:
- right_left_pris1 - right_gripper
action_ns: gripper_cmd action_ns: gripper_cmd
default: true default: true

View File

@ -1,157 +0,0 @@
<?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_bimanual_ros2_control" params="name initial_positions_file">
<xacro:property name="initial_positions" value="${load_yaml(initial_positions_file)['initial_positions']}"/>
<ros2_control name="${name}" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
</hardware>
<joint name="left_rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev1']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev2']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev3']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev4']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev5']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev6']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_rev7']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev1']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev2']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev3']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev4']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev5']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev6']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_rev7']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_left_pris1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['left_left_pris1']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_left_pris1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['right_left_pris1']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>

View File

@ -66,11 +66,11 @@
</group> </group>
<group name="left_gripper"> <group name="left_gripper">
<link name="left_link_left_jaw"/> <link name="left_link_left_jaw"/>
<joint name="left_left_pris1"/> <joint name="left_gripper"/>
</group> </group>
<group name="right_gripper"> <group name="right_gripper">
<link name="right_link_left_jaw"/> <link name="right_link_left_jaw"/>
<joint name="right_left_pris1"/> <joint name="right_gripper"/>
</group> </group>
<group name="left_side"> <group name="left_side">
<group name="left_arm"/> <group name="left_arm"/>
@ -86,7 +86,7 @@
</group> </group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="upper_body"> <group_state name="home" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0"/> <joint name="left_rev1" value="0"/>
<joint name="left_rev2" value="0"/> <joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0"/> <joint name="left_rev3" value="0"/>
@ -94,7 +94,7 @@
<joint name="left_rev5" value="0"/> <joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/> <joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/> <joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="0"/> <joint name="right_rev1" value="0"/>
<joint name="right_rev2" value="0"/> <joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/> <joint name="right_rev3" value="0"/>
@ -104,7 +104,7 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="ready" group="upper_body"> <group_state name="ready" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.2"/> <joint name="left_rev1" value="0.2"/>
<joint name="left_rev2" value="0"/> <joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0"/> <joint name="left_rev3" value="0"/>
@ -112,7 +112,7 @@
<joint name="left_rev5" value="0"/> <joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/> <joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/> <joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.2"/> <joint name="right_rev1" value="-0.2"/>
<joint name="right_rev2" value="0"/> <joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/> <joint name="right_rev3" value="0"/>
@ -122,22 +122,22 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="open" group="left_gripper"> <group_state name="open" group="left_gripper">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
</group_state> </group_state>
<group_state name="half_closed" group="left_gripper"> <group_state name="half_closed" group="left_gripper">
<joint name="left_left_pris1" value="-0.0225"/> <joint name="left_gripper" value="-0.0225"/>
</group_state> </group_state>
<group_state name="closed" group="left_gripper"> <group_state name="closed" group="left_gripper">
<joint name="left_left_pris1" value="-0.0451"/> <joint name="left_gripper" value="-0.0451"/>
</group_state> </group_state>
<group_state name="open" group="right_gripper"> <group_state name="open" group="right_gripper">
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
</group_state> </group_state>
<group_state name="half_closed" group="right_gripper"> <group_state name="half_closed" group="right_gripper">
<joint name="right_left_pris1" value="-0.0225"/> <joint name="right_gripper" value="-0.0225"/>
</group_state> </group_state>
<group_state name="center grip" group="upper_body"> <group_state name="center grip" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.2"/> <joint name="left_rev1" value="0.2"/>
<joint name="left_rev2" value="0"/> <joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0.3384"/> <joint name="left_rev3" value="0.3384"/>
@ -145,7 +145,7 @@
<joint name="left_rev5" value="0"/> <joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/> <joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/> <joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.2"/> <joint name="right_rev1" value="-0.2"/>
<joint name="right_rev2" value="0"/> <joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="-0.5"/> <joint name="right_rev3" value="-0.5"/>
@ -155,25 +155,25 @@
<joint name="right_rev7" value="0.0053"/> <joint name="right_rev7" value="0.0053"/>
</group_state> </group_state>
<group_state name="hands_up" group="upper_body"> <group_state name="hands_up" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.1"/> <joint name="left_rev1" value="0.1"/>
<joint name="left_rev2" value="0"/> <joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0"/> <joint name="left_rev3" value="0"/>
<joint name="left_rev4" value="2.7"/> <joint name="left_rev4" value="2.5"/>
<joint name="left_rev5" value="0"/> <joint name="left_rev5" value="0"/>
<joint name="left_rev6" value="0"/> <joint name="left_rev6" value="0"/>
<joint name="left_rev7" value="0"/> <joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.1"/> <joint name="right_rev1" value="-0.1"/>
<joint name="right_rev2" value="0"/> <joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/> <joint name="right_rev3" value="0"/>
<joint name="right_rev4" value="2.7"/> <joint name="right_rev4" value="2.5"/>
<joint name="right_rev5" value="0"/> <joint name="right_rev5" value="0"/>
<joint name="right_rev6" value="0"/> <joint name="right_rev6" value="0"/>
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="wave_1" group="upper_body"> <group_state name="wave_1" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.1"/> <joint name="left_rev1" value="0.1"/>
<joint name="left_rev2" value="0"/> <joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="-0.5179"/> <joint name="left_rev3" value="-0.5179"/>
@ -181,7 +181,7 @@
<joint name="left_rev5" value="-0.0116"/> <joint name="left_rev5" value="-0.0116"/>
<joint name="left_rev6" value="-0.5814"/> <joint name="left_rev6" value="-0.5814"/>
<joint name="left_rev7" value="0"/> <joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.1"/> <joint name="right_rev1" value="-0.1"/>
<joint name="right_rev2" value="0"/> <joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/> <joint name="right_rev3" value="0"/>
@ -191,7 +191,7 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="wave_2" group="upper_body"> <group_state name="wave_2" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.1"/> <joint name="left_rev1" value="0.1"/>
<joint name="left_rev2" value="0"/> <joint name="left_rev2" value="0"/>
<joint name="left_rev3" value="0.4541"/> <joint name="left_rev3" value="0.4541"/>
@ -199,7 +199,7 @@
<joint name="left_rev5" value="-0.0116"/> <joint name="left_rev5" value="-0.0116"/>
<joint name="left_rev6" value="-0.5814"/> <joint name="left_rev6" value="-0.5814"/>
<joint name="left_rev7" value="0"/> <joint name="left_rev7" value="0"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.1"/> <joint name="right_rev1" value="-0.1"/>
<joint name="right_rev2" value="0"/> <joint name="right_rev2" value="0"/>
<joint name="right_rev3" value="0"/> <joint name="right_rev3" value="0"/>
@ -209,7 +209,7 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="x" group="upper_body"> <group_state name="x" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="-0.2965"/> <joint name="left_rev1" value="-0.2965"/>
<joint name="left_rev2" value="-0.1745"/> <joint name="left_rev2" value="-0.1745"/>
<joint name="left_rev3" value="0.4513"/> <joint name="left_rev3" value="0.4513"/>
@ -217,7 +217,7 @@
<joint name="left_rev5" value="0.5207"/> <joint name="left_rev5" value="0.5207"/>
<joint name="left_rev6" value="-0.3384"/> <joint name="left_rev6" value="-0.3384"/>
<joint name="left_rev7" value="-0.0795"/> <joint name="left_rev7" value="-0.0795"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="0.4715"/> <joint name="right_rev1" value="0.4715"/>
<joint name="right_rev2" value="-0.1224"/> <joint name="right_rev2" value="-0.1224"/>
<joint name="right_rev3" value="-1.0298"/> <joint name="right_rev3" value="-1.0298"/>
@ -227,7 +227,7 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="swing_arm_left_forward" group="upper_body"> <group_state name="swing_arm_left_forward" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="-0.6147"/> <joint name="left_rev1" value="-0.6147"/>
<joint name="left_rev2" value="-0.0356"/> <joint name="left_rev2" value="-0.0356"/>
<joint name="left_rev3" value="0.081"/> <joint name="left_rev3" value="0.081"/>
@ -235,7 +235,7 @@
<joint name="left_rev5" value="0.5207"/> <joint name="left_rev5" value="0.5207"/>
<joint name="left_rev6" value="-0.3384"/> <joint name="left_rev6" value="-0.3384"/>
<joint name="left_rev7" value="-0.0795"/> <joint name="left_rev7" value="-0.0795"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.3876"/> <joint name="right_rev1" value="-0.3876"/>
<joint name="right_rev2" value="0.0858"/> <joint name="right_rev2" value="0.0858"/>
<joint name="right_rev3" value="-0.567"/> <joint name="right_rev3" value="-0.567"/>
@ -245,7 +245,7 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="swing_arm_right_forward" group="upper_body"> <group_state name="swing_arm_right_forward" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.2762"/> <joint name="left_rev1" value="0.2762"/>
<joint name="left_rev2" value="0.1553"/> <joint name="left_rev2" value="0.1553"/>
<joint name="left_rev3" value="0.081"/> <joint name="left_rev3" value="0.081"/>
@ -253,7 +253,7 @@
<joint name="left_rev5" value="-0.4281"/> <joint name="left_rev5" value="-0.4281"/>
<joint name="left_rev6" value="-0.3384"/> <joint name="left_rev6" value="-0.3384"/>
<joint name="left_rev7" value="-0.0795"/> <joint name="left_rev7" value="-0.0795"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="0.4556"/> <joint name="right_rev1" value="0.4556"/>
<joint name="right_rev2" value="-0.0009"/> <joint name="right_rev2" value="-0.0009"/>
<joint name="right_rev3" value="-0.567"/> <joint name="right_rev3" value="-0.567"/>
@ -263,7 +263,7 @@
<joint name="right_rev7" value="0"/> <joint name="right_rev7" value="0"/>
</group_state> </group_state>
<group_state name="siu" group="upper_body"> <group_state name="siu" group="upper_body">
<joint name="left_left_pris1" value="0"/> <joint name="left_gripper" value="0"/>
<joint name="left_rev1" value="0.4512"/> <joint name="left_rev1" value="0.4512"/>
<joint name="left_rev2" value="0.2421"/> <joint name="left_rev2" value="0.2421"/>
<joint name="left_rev3" value="0.081"/> <joint name="left_rev3" value="0.081"/>
@ -271,7 +271,7 @@
<joint name="left_rev5" value="-0.4281"/> <joint name="left_rev5" value="-0.4281"/>
<joint name="left_rev6" value="-0.3384"/> <joint name="left_rev6" value="-0.3384"/>
<joint name="left_rev7" value="-0.1326"/> <joint name="left_rev7" value="-0.1326"/>
<joint name="right_left_pris1" value="0"/> <joint name="right_gripper" value="0"/>
<joint name="right_rev1" value="-0.4035"/> <joint name="right_rev1" value="-0.4035"/>
<joint name="right_rev2" value="0.19"/> <joint name="right_rev2" value="0.19"/>
<joint name="right_rev3" value="-0.567"/> <joint name="right_rev3" value="-0.567"/>
@ -286,8 +286,8 @@
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)--> <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="base_link" child_link="pedestal_link"/> <virtual_joint name="virtual_joint" type="fixed" parent_frame="base_link" child_link="pedestal_link"/>
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated--> <!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="left_right_pris2"/> <passive_joint name="left_gripper_mimic"/>
<passive_joint name="right_right_pris2"/> <passive_joint name="right_gripper_mimic"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="camera_link" link2="pedestal_link" reason="Adjacent"/> <disable_collisions link1="camera_link" link2="pedestal_link" reason="Adjacent"/>
<disable_collisions link1="left_link1" link2="left_link2" reason="Adjacent"/> <disable_collisions link1="left_link1" link2="left_link2" reason="Adjacent"/>

View File

@ -16,6 +16,7 @@
--> -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" /> <xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
<xacro:arg name="hardware_type" default="real" />
<!-- Import openarm_bimanual urdf file --> <!-- Import openarm_bimanual urdf file -->
<xacro:include filename="$(find openarm_bimanual_description)/urdf/openarm_bimanual.urdf.xacro" /> <xacro:include filename="$(find openarm_bimanual_description)/urdf/openarm_bimanual.urdf.xacro" />
@ -26,10 +27,5 @@
<child link="base_link"/> <child link="base_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint> </joint>
<!-- Import control_xacro -->
<!-- <xacro:include filename="openarm_bimanual.ros2_control.xacro" />
<xacro:openarm_bimanual_ros2_control name="FakeSystem" initial_positions_file="$(arg initial_positions_file)"/> -->
</robot> </robot>

View File

@ -82,10 +82,10 @@ right_arm_controller:
- velocity - velocity
left_gripper_controller: left_gripper_controller:
ros__parameters: ros__parameters:
joint: left_left_pris1 joint: left_gripper
right_gripper_controller: right_gripper_controller:
ros__parameters: ros__parameters:
joint: right_left_pris1 joint: right_gripper
left_side_controller: left_side_controller:
ros__parameters: ros__parameters:
joints: joints:
@ -96,7 +96,7 @@ left_side_controller:
- left_rev5 - left_rev5
- left_rev6 - left_rev6
- left_rev7 - left_rev7
- left_left_pris1 - left_gripper
command_interfaces: command_interfaces:
- position - position
- velocity - velocity
@ -113,7 +113,7 @@ right_side_controller:
- right_rev5 - right_rev5
- right_rev6 - right_rev6
- right_rev7 - right_rev7
- right_left_pris1 - right_gripper
command_interfaces: command_interfaces:
- position - position
- velocity - velocity
@ -130,7 +130,7 @@ upper_body_controller:
- left_rev5 - left_rev5
- left_rev6 - left_rev6
- left_rev7 - left_rev7
- left_left_pris1 - left_gripper
- right_rev1 - right_rev1
- right_rev2 - right_rev2
- right_rev3 - right_rev3
@ -138,7 +138,7 @@ upper_body_controller:
- right_rev5 - right_rev5
- right_rev6 - right_rev6
- right_rev7 - right_rev7
- right_left_pris1 - right_gripper
command_interfaces: command_interfaces:
- position - position
- velocity - velocity

View File

@ -14,9 +14,53 @@
from moveit_configs_utils import MoveItConfigsBuilder from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_demo_launch from moveit_configs_utils.launches import generate_demo_launch
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, Command, PathJoinSubstitution, FindExecutable
from launch_ros.substitutions import FindPackageShare
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( declared_arguments = []
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() declared_arguments.append(
return generate_demo_launch(moveit_config) DeclareLaunchArgument(
"hardware_type",
default_value="real",
description="Hardware interface type: 'real', 'sim' (MuJoCo), or 'mock'",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable writable sensor interfaces when using mock hardware",
)
)
hardware_type = LaunchConfiguration("hardware_type")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
moveit_config = (
MoveItConfigsBuilder("openarm_bimanual",
package_name="openarm_bimanual_moveit_config")
.robot_description(
file_path="config/openarm_bimanual.urdf.xacro",
mappings={
"hardware_type": hardware_type,
"mock_sensor_commands": mock_sensor_commands,
},
)
.to_moveit_configs()
)
demo_ld = generate_demo_launch(moveit_config)
ld = LaunchDescription()
for arg in declared_arguments:
ld.add_action(arg)
for entity in demo_ld.entities:
ld.add_action(entity)
return ld

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_move_group_launch
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_move_group_launch(moveit_config) return generate_move_group_launch(moveit_config)

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_moveit_rviz_launch
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_moveit_rviz_launch(moveit_config) return generate_moveit_rviz_launch(moveit_config)

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_rsp_launch
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_rsp_launch(moveit_config) return generate_rsp_launch(moveit_config)

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_setup_assistant_launch
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_setup_assistant_launch(moveit_config) return generate_setup_assistant_launch(moveit_config)

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_spawn_controllers_launch
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_spawn_controllers_launch(moveit_config) return generate_spawn_controllers_launch(moveit_config)

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_laun
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_static_virtual_joint_tfs_launch(moveit_config) return generate_static_virtual_joint_tfs_launch(moveit_config)

View File

@ -18,5 +18,6 @@ from moveit_configs_utils.launches import generate_warehouse_db_launch
def generate_launch_description(): def generate_launch_description():
moveit_config = MoveItConfigsBuilder( moveit_config = MoveItConfigsBuilder(
"openarm_bimanual", package_name="openarm_bimanual_moveit_config").to_moveit_configs() "openarm_bimanual", package_name="openarm_bimanual_moveit_config"
).to_moveit_configs()
return generate_warehouse_db_launch(moveit_config) return generate_warehouse_db_launch(moveit_config)

View File

@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and # See the License for the specific language governing permissions and
# limitations under the License. # limitations under the License.
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.22)
project(openarm_bringup) project(openarm_bringup)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")

View File

@ -23,7 +23,12 @@
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction
from launch.event_handlers import OnProcessExit, OnProcessStart from launch.event_handlers import OnProcessExit, OnProcessStart
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution from launch.substitutions import (
Command,
FindExecutable,
LaunchConfiguration,
PathJoinSubstitution,
)
from launch_ros.actions import Node from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare from launch_ros.substitutions import FindPackageShare
@ -72,9 +77,9 @@ def generate_launch_description():
) )
declared_arguments.append( declared_arguments.append(
DeclareLaunchArgument( DeclareLaunchArgument(
"use_mock_hardware", "hardware_type",
default_value="false", default_value="real",
description="Start robot with mock hardware mirroring command to its states.", description="Hardware interface type: 'real', 'sim' (MuJoCo), or 'mock'",
) )
) )
declared_arguments.append( declared_arguments.append(
@ -82,7 +87,7 @@ def generate_launch_description():
"mock_sensor_commands", "mock_sensor_commands",
default_value="false", default_value="false",
description="Enable mock command interfaces for sensors used for simple simulations. \ description="Enable mock command interfaces for sensors used for simple simulations. \
Used only if 'use_mock_hardware' parameter is true.", Used only if 'hardware_type' parameter is 'mock'.",
) )
) )
declared_arguments.append( declared_arguments.append(
@ -101,7 +106,7 @@ def generate_launch_description():
description_package = LaunchConfiguration("description_package") description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file") description_file = LaunchConfiguration("description_file")
prefix = LaunchConfiguration("prefix") prefix = LaunchConfiguration("prefix")
use_mock_hardware = LaunchConfiguration("use_mock_hardware") hardware_type = LaunchConfiguration("hardware_type")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands") mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
robot_controller = LaunchConfiguration("robot_controller") robot_controller = LaunchConfiguration("robot_controller")
@ -118,8 +123,8 @@ def generate_launch_description():
"prefix:=", "prefix:=",
prefix, prefix,
" ", " ",
"use_mock_hardware:=", "hardware_type:=",
use_mock_hardware, hardware_type,
" ", " ",
"mock_sensor_commands:=", "mock_sensor_commands:=",
mock_sensor_commands, mock_sensor_commands,
@ -133,8 +138,7 @@ def generate_launch_description():
[FindPackageShare(runtime_config_package), "config", controllers_file] [FindPackageShare(runtime_config_package), "config", controllers_file]
) )
rviz_config_file = PathJoinSubstitution( rviz_config_file = PathJoinSubstitution(
[FindPackageShare(description_package), "rviz", [FindPackageShare(description_package), "rviz", "openarm.rviz"]
"robot_description.rviz"]
) )
control_node = Node( control_node = Node(
@ -160,8 +164,11 @@ def generate_launch_description():
joint_state_broadcaster_spawner = Node( joint_state_broadcaster_spawner = Node(
package="controller_manager", package="controller_manager",
executable="spawner", executable="spawner",
arguments=["joint_state_broadcaster", arguments=[
"--controller-manager", "/controller_manager"], "joint_state_broadcaster",
"--controller-manager",
"/controller_manager",
],
) )
robot_controller_names = [robot_controller] robot_controller_names = [robot_controller]
@ -188,7 +195,8 @@ def generate_launch_description():
] ]
# Delay loading and activation of `joint_state_broadcaster` after start of ros2_control_node # Delay loading and activation of `joint_state_broadcaster` after start of ros2_control_node
delay_joint_state_broadcaster_spawner_after_ros2_control_node = RegisterEventHandler( delay_joint_state_broadcaster_spawner_after_ros2_control_node = (
RegisterEventHandler(
event_handler=OnProcessStart( event_handler=OnProcessStart(
target_action=control_node, target_action=control_node,
on_start=[ on_start=[
@ -199,6 +207,7 @@ def generate_launch_description():
], ],
) )
) )
)
# Delay loading and activation of robot_controller_names after `joint_state_broadcaster` # Delay loading and activation of robot_controller_names after `joint_state_broadcaster`
delay_robot_controller_spawners_after_joint_state_broadcaster_spawner = [] delay_robot_controller_spawners_after_joint_state_broadcaster_spawner = []

View File

@ -28,8 +28,11 @@ from launch_ros.substitutions import FindPackageShare
def generate_launch_description(): def generate_launch_description():
position_goals = PathJoinSubstitution( position_goals = PathJoinSubstitution(
[FindPackageShare("openarm_bringup"), "config", [
"test_goal_publishers_config.yaml"] FindPackageShare("openarm_bringup"),
"config",
"test_goal_publishers_config.yaml",
]
) )
return LaunchDescription( return LaunchDescription(

View File

@ -28,8 +28,11 @@ from launch_ros.substitutions import FindPackageShare
def generate_launch_description(): def generate_launch_description():
position_goals = PathJoinSubstitution( position_goals = PathJoinSubstitution(
[FindPackageShare("openarm_bringup"), "config", [
"test_goal_publishers_config.yaml"] FindPackageShare("openarm_bringup"),
"config",
"test_goal_publishers_config.yaml",
]
) )
return LaunchDescription( return LaunchDescription(

View File

@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and # See the License for the specific language governing permissions and
# limitations under the License. # limitations under the License.
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.22)
project(openarm_description) project(openarm_description)
find_package(ament_cmake REQUIRED) find_package(ament_cmake REQUIRED)

View File

@ -15,8 +15,8 @@
# Default initial positions for openarm's ros2_control fake system # Default initial positions for openarm's ros2_control fake system
initial_positions: initial_positions:
left_pris1: 0 gripper: 0
right_pris2: 0 gripper_mimic: 0
rev1: 0 rev1: 0
rev2: 0 rev2: 0
rev3: 0 rev3: 0

View File

@ -37,34 +37,52 @@ def generate_launch_description():
description="Absolute path to the robot's URDF file", description="Absolute path to the robot's URDF file",
) )
side_arg = DeclareLaunchArgument( side_arg = DeclareLaunchArgument(
name="side", default_value="right", # Use "left" to test left arm. name="side",
description="Select arm side: 'left' or 'right'" default_value="right", # Use "left" to test left arm.
description="Select arm side: 'left' or 'right'",
) )
zero_pos_arg = DeclareLaunchArgument( zero_pos_arg = DeclareLaunchArgument(
# Use "arm" to test alternative configuration. name="zero_pos",
name="zero_pos", default_value="up", default_value="up", # Use "arm" to test alternative configuration.
description="Specify zero position: 'up' or 'arm'" description="Specify zero position: 'up' or 'arm'",
) )
prefix_arg = DeclareLaunchArgument( prefix_arg = DeclareLaunchArgument(
name="prefix", default_value="", name="prefix",
description="Prefix for link and joint names (e.g., left_, right_)" default_value="",
description="Prefix for link and joint names (e.g., left_, right_)",
) )
can_device_arg = DeclareLaunchArgument( can_device_arg = DeclareLaunchArgument(
name="can_device", default_value="can0", name="can_device",
description="CAN device identifier to use" default_value="can0",
description="CAN device identifier to use",
)
hardware_type_arg = DeclareLaunchArgument(
name="hardware_type",
default_value="real",
description="Hardware interface type: 'real', 'sim' (MuJoCo), or 'mock'",
) )
use_sim_time = LaunchConfiguration("use_sim_time") use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument( use_sim_time_launch_arg = DeclareLaunchArgument(
"use_sim_time", default_value="true") "use_sim_time", default_value="true"
)
robot_description_command = Command([ robot_description_command = Command(
"xacro ", LaunchConfiguration("model"), [
" side:=", LaunchConfiguration("side"), "xacro ",
" zero_pos:=", LaunchConfiguration("zero_pos"), LaunchConfiguration("model"),
" prefix:=", LaunchConfiguration("prefix"), " side:=",
" can_device:=", LaunchConfiguration("can_device") LaunchConfiguration("side"),
]) " zero_pos:=",
LaunchConfiguration("zero_pos"),
" prefix:=",
LaunchConfiguration("prefix"),
" can_device:=",
LaunchConfiguration("can_device"),
" hardware_type:=",
LaunchConfiguration("hardware_type"),
]
)
robot_state_publisher_node = launch_ros.actions.Node( robot_state_publisher_node = launch_ros.actions.Node(
package="robot_state_publisher", package="robot_state_publisher",
@ -87,6 +105,7 @@ def generate_launch_description():
zero_pos_arg, zero_pos_arg,
prefix_arg, prefix_arg,
can_device_arg, can_device_arg,
hardware_type_arg,
use_sim_time_launch_arg, use_sim_time_launch_arg,
robot_state_publisher_node, robot_state_publisher_node,
] ]

View File

@ -46,7 +46,10 @@ def generate_launch_description():
), ),
] ]
), ),
launch_arguments=dict(use_sim_time=use_sim_time).items(), launch_arguments=dict(
use_sim_time=use_sim_time,
hardware_type=LaunchConfiguration("hardware_type")
).items(),
) )
joint_state_publisher_node = launch_ros.actions.Node( joint_state_publisher_node = launch_ros.actions.Node(
@ -107,6 +110,11 @@ def generate_launch_description():
default_value=str(default_rviz_config_path), default_value=str(default_rviz_config_path),
description="Absolute path to rviz config file", description="Absolute path to rviz config file",
), ),
launch.actions.DeclareLaunchArgument(
name="hardware_type",
default_value="real",
description="Hardware interface type: 'real', 'sim' (MuJoCo), or 'mock'",
),
joint_state_publisher_node, joint_state_publisher_node,
joint_state_publisher_gui_node, joint_state_publisher_gui_node,
robot_state_publisher_node, robot_state_publisher_node,

View File

@ -37,7 +37,8 @@ def generate_launch_description():
# Make path to resources dir without last package_name fragment. # Make path to resources dir without last package_name fragment.
path_to_share_dir_clipped = "".join( path_to_share_dir_clipped = "".join(
get_package_share_directory(resources_package).rsplit( get_package_share_directory(resources_package).rsplit(
"/" + resources_package, 1) "/" + resources_package, 1
)
) )
# Gazebo hint for resources. # Gazebo hint for resources.
@ -57,10 +58,12 @@ def generate_launch_description():
use_custom_world = LaunchConfiguration("use_custom_world") use_custom_world = LaunchConfiguration("use_custom_world")
use_custom_world_launch_arg = DeclareLaunchArgument( use_custom_world_launch_arg = DeclareLaunchArgument(
"use_custom_world", default_value="true") "use_custom_world", default_value="true"
)
gazebo_world = LaunchConfiguration("gazebo_world") gazebo_world = LaunchConfiguration("gazebo_world")
gazebo_world_launch_arg = DeclareLaunchArgument( gazebo_world_launch_arg = DeclareLaunchArgument(
"gazebo_world", default_value="empty.sdf") "gazebo_world", default_value="empty.sdf"
)
# prepare custom world # prepare custom world
world = os.getenv("GZ_SIM_WORLD", "empty") world = os.getenv("GZ_SIM_WORLD", "empty")
@ -78,9 +81,11 @@ def generate_launch_description():
PythonLaunchDescriptionSource( PythonLaunchDescriptionSource(
os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py"), os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py"),
), ),
launch_arguments=launch_arguments launch_arguments=(
launch_arguments
if use_custom_world if use_custom_world
else dict(gz_args="-r " + gazebo_world + " --verbose").items(), else dict(gz_args="-r " + gazebo_world + " --verbose").items()
),
) )
# Spawn # Spawn
@ -104,7 +109,8 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time") use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument( use_sim_time_launch_arg = DeclareLaunchArgument(
"use_sim_time", default_value="true") "use_sim_time", default_value="true"
)
use_rviz = LaunchConfiguration("use_rviz") use_rviz = LaunchConfiguration("use_rviz")
use_rviz_arg = DeclareLaunchArgument("use_rviz", default_value="true") use_rviz_arg = DeclareLaunchArgument("use_rviz", default_value="true")

View File

@ -31,6 +31,8 @@
<xacro:property name="reflect" value="${1 if side=='right' else -1}"/> <xacro:property name="reflect" value="${1 if side=='right' else -1}"/>
<xacro:property name="rotate" value="${0 if side=='right' else pi}"/> <xacro:property name="rotate" value="${0 if side=='right' else pi}"/>
<!-- ros2_control configuration is handled separately in openarm.urdf.xacro -->
<link name="${prefix}dummy_link"/> <link name="${prefix}dummy_link"/>
<joint name="${prefix}dummy_joint" type="fixed"> <joint name="${prefix}dummy_joint" type="fixed">
@ -288,20 +290,21 @@
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="${-pi * 11.0 / 36.0}" upper="${pi * 11.0 / 36.0}" velocity="0.0"/> <limit effort="0.0" lower="${-pi * 11.0 / 36.0}" upper="${pi * 11.0 / 36.0}" velocity="0.0"/>
</joint> </joint>
<joint name="${prefix}left_pris1" type="prismatic"> <!-- this is used as the actuator interface, the other gripper mimics motion -->
<joint name="${prefix}gripper" type="prismatic">
<parent link="${prefix}link8"/> <parent link="${prefix}link8"/>
<child link="${prefix}link_left_jaw"/> <child link="${prefix}link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/> <origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint> </joint>
<joint name="${prefix}right_pris2" type="prismatic"> <joint name="${prefix}gripper_mimic" type="prismatic">
<parent link="${prefix}link8"/> <parent link="${prefix}link8"/>
<child link="${prefix}link_right_jaw"/> <child link="${prefix}link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/> <origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="${prefix}left_pris1" multiplier="-1.0" offset="0.0"/> <mimic joint="${prefix}gripper" multiplier="-1.0" offset="0.0"/>
</joint> </joint>
<joint name="${prefix}virtual_gripper_center" type="fixed"> <joint name="${prefix}virtual_gripper_center" type="fixed">
<parent link="${prefix}link8"/> <parent link="${prefix}link8"/>

View File

@ -15,83 +15,104 @@
 limitations under the License.  limitations under the License.
--> -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="openarm_ros2_control" params="name initial_positions_file prefix:='' can_device='can0' use_mock_hardware:=false mock_sensor_commands:=false"> <xacro:macro name="openarm_ros2_control" params="name initial_positions_file websocket_port='' prefix:='' can_device='can0' hardware_type='real' mock_sensor_commands='{}'">
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/> <xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
<!-- Set default websocket ports based on prefix if not provided -->
<xacro:if value="${hardware_type == 'sim' and websocket_port == ''}">
<xacro:property name="computed_websocket_port" value="${'1337' if prefix == 'right_' or prefix == '' else '1338'}"/>
</xacro:if>
<xacro:unless value="${hardware_type == 'sim' and websocket_port == ''}">
<xacro:property name="computed_websocket_port" value="${websocket_port}"/>
</xacro:unless>
<ros2_control name="${prefix}${name}" type="system"> <ros2_control name="${prefix}${name}" type="system">
<hardware> <hardware>
<xacro:if value="${use_mock_hardware}"> <xacro:if value="${hardware_type == 'mock'}">
<plugin>mock_components/GenericSystem</plugin> <plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param> <param name="mock_sensor_commands">${mock_sensor_commands}</param>
</xacro:if> </xacro:if>
<xacro:unless value="${use_mock_hardware}"> <xacro:if value="${hardware_type == 'sim'}">
<plugin>openarm_mujoco_hardware/MujocoHardware</plugin>
<param name="prefix">${prefix}</param>
<xacro:if value="${computed_websocket_port != ''}">
<param name="websocket_port">${computed_websocket_port}</param>
</xacro:if>
</xacro:if>
<xacro:if value="${hardware_type == 'real'}">
<plugin>openarm_hardware/OpenArmHW</plugin> <plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix">${prefix}</param> <param name="prefix">${prefix}</param>
<param name="can_device">${can_device}</param> <param name="can_device">${can_device}</param>
</xacro:unless> </xacro:if>
</hardware> </hardware>
<joint name="${prefix}rev1"> <joint name="${prefix}rev1">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}rev2"> <joint name="${prefix}rev2">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}rev3"> <joint name="${prefix}rev3">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}rev4"> <joint name="${prefix}rev4">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}rev5"> <joint name="${prefix}rev5">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}rev6"> <joint name="${prefix}rev6">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}rev7"> <joint name="${prefix}rev7">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="${prefix}left_pris1"> <joint name="${prefix}gripper">
<command_interface name="position"/> <command_interface name="position"/>
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
</joint> </joint>
<!-- <joint name="${prefix}gripper_mimic">
<state_interface name="position">
<param name="initial_value">${initial_positions['gripper_mimic']}</param>
</state_interface>
</joint> -->
</ros2_control> </ros2_control>
</xacro:macro> </xacro:macro>
</robot> </robot>

View File

@ -1,6 +1,6 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from openarm_description/urdf/openarm.urdf.xacro | --> <!-- | This document was autogenerated by xacro from openarm.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- <!--
@ -28,6 +28,7 @@
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<!-- ros2_control configuration is handled separately in openarm.urdf.xacro -->
<link name="dummy_link"/> <link name="dummy_link"/>
<joint name="dummy_joint" type="fixed"> <joint name="dummy_joint" type="fixed">
<parent link="dummy_link"/> <parent link="dummy_link"/>
@ -283,20 +284,21 @@
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.9599310885968811" upper="0.9599310885968811" velocity="0.0"/> <limit effort="0.0" lower="-0.9599310885968811" upper="0.9599310885968811" velocity="0.0"/>
</joint> </joint>
<joint name="left_pris1" type="prismatic"> <!-- this is used as the actuator interface, the other gripper mimics motion -->
<joint name="gripper" type="prismatic">
<parent link="link8"/> <parent link="link8"/>
<child link="link_left_jaw"/> <child link="link_left_jaw"/>
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/> <origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.1"/>
</joint> </joint>
<joint name="right_pris2" type="prismatic"> <joint name="gripper_mimic" type="prismatic">
<parent link="link8"/> <parent link="link8"/>
<child link="link_right_jaw"/> <child link="link_right_jaw"/>
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/> <origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
<limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/> <limit effort="0.0" lower="-0.0451" upper="0.0" velocity="0.0"/>
<mimic joint="left_pris1" multiplier="-1.0" offset="0.0"/> <mimic joint="gripper" multiplier="-1.0" offset="0.0"/>
</joint> </joint>
<joint name="virtual_gripper_center" type="fixed"> <joint name="virtual_gripper_center" type="fixed">
<parent link="link8"/> <parent link="link8"/>
@ -305,69 +307,75 @@
</joint> </joint>
<ros2_control name="OpenArmHW" type="system"> <ros2_control name="OpenArmHW" type="system">
<hardware> <hardware>
<plugin>mock_components/GenericSystem</plugin> <plugin>openarm_hardware/OpenArmHW</plugin>
<param name="mock_sensor_commands">False</param> <param name="prefix"></param>
<param name="can_device">can0</param>
</hardware> </hardware>
<joint name="rev1"> <joint name="rev1">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="rev2"> <joint name="rev2">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="rev3"> <joint name="rev3">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="rev4"> <joint name="rev4">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="rev5"> <joint name="rev5">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="rev6"> <joint name="rev6">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="rev7"> <joint name="rev7">
<command_interface name="position"/> <command_interface name="position"/>
<command_interface name="velocity"/> <command_interface name="velocity"/>
<command_interface name="effort"/> <!-- <command_interface name="effort"/> -->
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <!-- <state_interface name="effort"/> -->
</joint> </joint>
<joint name="left_pris1"> <joint name="gripper">
<command_interface name="position"/> <command_interface name="position"/>
<state_interface name="position"/> <state_interface name="position"/>
<state_interface name="velocity"/> <state_interface name="velocity"/>
</joint> </joint>
<!-- <joint name="${prefix}gripper_mimic">
<state_interface name="position">
<param name="initial_value">${initial_positions['gripper_mimic']}</param>
</state_interface>
</joint> -->
</ros2_control> </ros2_control>
</robot> </robot>

View File

@ -22,7 +22,7 @@
<!-- Control-related parameters --> <!-- Control-related parameters -->
<xacro:arg name="can_device" default="can0" /> <xacro:arg name="can_device" default="can0" />
<xacro:arg name="use_mock_hardware" default="false" /> <xacro:arg name="hardware_type" default="real" />
<xacro:arg name="mock_sensor_commands" default="false" /> <xacro:arg name="mock_sensor_commands" default="false" />
<!-- Include robot description (without control parameters) --> <!-- Include robot description (without control parameters) -->
@ -32,6 +32,6 @@
<!-- Include control configuration (with only control parameters) --> <!-- Include control configuration (with only control parameters) -->
<xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro"/> <xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro"/>
<xacro:arg name="initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" /> <xacro:arg name="initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="OpenArmHW" prefix="$(arg prefix)" initial_positions_file="$(arg initial_positions_file)" can_device="$(arg can_device)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/> <xacro:openarm_ros2_control name="OpenArmHW" prefix="$(arg prefix)" initial_positions_file="$(arg initial_positions_file)" can_device="$(arg can_device)" hardware_type="$(arg hardware_type)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
</robot> </robot>

View File

@ -13,7 +13,7 @@
# limitations under the License. # limitations under the License.
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.22)
project(openarm_hardware) project(openarm_hardware)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")

View File

@ -102,14 +102,14 @@ class TestOpenArmHW : public ::testing::Test {
<state_interface name="velocity"/> <state_interface name="velocity"/>
<state_interface name="effort"/> <state_interface name="effort"/>
</joint> </joint>
<joint name="left_pris1"> <joint name="gripper">
<command_interface name="position"/> <command_interface name="position"/>
<state_interface name="position"> <state_interface name="position">
<param name="initial_value">0</param> <param name="initial_value">0</param>
</state_interface> </state_interface>
<state_interface name="velocity"/> <state_interface name="velocity"/>
</joint> </joint>
<joint name="right_pris2"> <joint name="gripper_mimic">
<state_interface name="position"> <state_interface name="position">
<param name="initial_value">0</param> <param name="initial_value">0</param>
</state_interface> </state_interface>

View File

@ -0,0 +1,98 @@
# 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.
cmake_minimum_required(VERSION 3.22)
project(openarm_mujoco_hardware)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(Boost REQUIRED)
find_package(nlohmann_json REQUIRED)
add_library(${PROJECT_NAME} SHARED
src/openarm_mujoco_hardware.cpp
)
target_include_directories(
${PROJECT_NAME}
PRIVATE
include
)
ament_target_dependencies(${PROJECT_NAME} PUBLIC
hardware_interface
pluginlib
rclcpp
rclcpp_lifecycle
)
pluginlib_export_plugin_description_file(hardware_interface openarm_mujoco_hardware.xml)
target_link_libraries(${PROJECT_NAME} PRIVATE Boost::headers nlohmann_json::nlohmann_json)
install(
TARGETS ${PROJECT_NAME}
DESTINATION lib
)
install(DIRECTORY include/
DESTINATION include
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gmock REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(ros2_control_test_assets REQUIRED)
ament_add_gmock(test_openarm_mujoco_hardware
test/test_load_openarm_mujoco_hardware.cpp
)
target_link_libraries(test_openarm_mujoco_hardware
${PROJECT_NAME}
)
ament_target_dependencies(test_openarm_mujoco_hardware
hardware_interface
ros2_control_test_assets
)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_export_include_directories(
include
)
ament_export_libraries(
${PROJECT_NAME}
)
ament_export_dependencies(
hardware_interface
pluginlib
rclcpp
)
ament_package()

View File

@ -0,0 +1,202 @@
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "[]"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright [yyyy] [name of copyright owner]
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.

View File

@ -0,0 +1,42 @@
# OpenArm MuJoCo Hardware Interface
This package provides a ros2_control hardware interface for simulating OpenArm using the MuJoCo physics engine in place of physical hardware. It connects to a WebAssembly instance of MuJoCo through WebSockets.
## Usage
Certain OpenArm packages have been configured to use this interface by specifying the `hardware_type` flag.
This flag defaults to `real`, which assumes the use of physical hardware.
Setting the flag to `mock` uses an interface that writes commands to states directly (with some delays).
Setting the flag to `sim` uses the MuJoCo hardware interface.
For example, to use MoveIt2 with simulated bimanual hardware, first run MuJoCo by visiting:
[github.com/thomasonzhou/mujoco_anywhere](https://github.com/thomasonzhou/mujoco_anywhere)
Then run the original command with the `hardware_type` flag:
```sh
ros2 launch -d openarm_bimanual_moveit_config demo.launch.py hardware_type:=sim
```
*It may be necessary to install the nlohmann-json-dev library before building*
Please note that running multiple instances of the website will cause conflicting signals. Future configurations will allow for multiple instances to run simultaneously.
## Configuration
### Hardware Plugin Config
The hardware plugin is specified in `openarm_description/openarm.ros2_control.xacro` as follows:
```xml
<ros2_control name="openarm_system" type="system">
<hardware>
<plugin>openarm_mujoco_hardware/MujocoHardware</plugin>
<param name="prefix">left_</param>
<param name="websocket_port">1337</param>
</hardware>
<!-- Joint configurations -->
</ros2_control>
```
When using OpenArm in a bimanual configuration, the WebSocket ports default to 1337 for right arm and 1338 for left arm commands. However, in practice commands can be sent and states can be received through any connected port.

View File

@ -0,0 +1,123 @@
// 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.
#pragma once
#include <boost/asio.hpp>
#include <boost/beast/core.hpp>
#include <boost/beast/websocket.hpp>
#include <deque>
#include <iostream>
#include <mutex>
#include <nlohmann/json.hpp>
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
namespace openarm_mujoco_hardware {
class WebSocketSession;
class MujocoHardware : public hardware_interface::SystemInterface {
public:
MujocoHardware() = default;
hardware_interface::CallbackReturn on_init(
const hardware_interface::HardwareInfo& info) override;
hardware_interface::CallbackReturn on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) override;
hardware_interface::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State& /*previous_state*/) override;
hardware_interface::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State& /*previous_state*/) override;
hardware_interface::CallbackReturn on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) override;
hardware_interface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State& /*previous_state*/) override;
hardware_interface::CallbackReturn on_error(
const rclcpp_lifecycle::State& /*previous_state*/) override;
std::vector<hardware_interface::StateInterface> export_state_interfaces()
override;
std::vector<hardware_interface::CommandInterface> export_command_interfaces()
override;
hardware_interface::return_type read(
const rclcpp::Time& /*time*/,
const rclcpp::Duration& /*period*/) override;
hardware_interface::return_type write(
const rclcpp::Time& /*time*/,
const rclcpp::Duration& /*period*/) override;
friend class WebSocketSession;
private:
static constexpr size_t TOTAL_DOF =
8; // Total degrees of freedom, including gripper
inline static constexpr std::array<double, TOTAL_DOF> KP_ = {
180.0, 180.0, 140.0, 155.0, 115.0, 115.0, 115.0, 25.0};
inline static constexpr std::array<double, TOTAL_DOF> KD_ = {
0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01};
static constexpr double MAX_MOTOR_TORQUE = 100.0;
std::vector<double> qpos_;
std::vector<double> qvel_;
std::vector<double> qtau_;
std::vector<double> cmd_qpos_;
std::vector<double> cmd_qvel_;
std::vector<double> cmd_qtau_ff_;
std::mutex state_mutex_;
void clear_cmd_torque();
// websocket connection to mujoco
boost::asio::ip::tcp::endpoint endpoint_;
boost::asio::ip::address address_;
static constexpr double kDefaultWebsocketPort = 1337;
unsigned short websocket_port_;
boost::asio::io_context ioc_{};
boost::asio::ip::tcp::acceptor acceptor_{ioc_};
std::thread ioc_thread_;
std::shared_ptr<WebSocketSession> ws_session_;
void start_accept();
const std::string kMuJoCoWebSocketURL_ =
"https://thomasonzhou.github.io/mujoco_anywhere/";
};
class WebSocketSession : public std::enable_shared_from_this<WebSocketSession> {
public:
static std::shared_ptr<WebSocketSession> create(
boost::asio::ip::tcp::socket socket, MujocoHardware* hw);
void run();
WebSocketSession(boost::asio::ip::tcp::socket socket, MujocoHardware* hw);
void send_json(const nlohmann::json& j);
private:
void flush();
void do_handshake();
void on_accept(boost::beast::error_code ec);
void do_read();
void on_read(boost::beast::error_code ec, std::size_t);
boost::beast::websocket::stream<boost::asio::ip::tcp::socket> ws_;
boost::beast::flat_buffer buffer_;
MujocoHardware* hw_;
std::deque<std::shared_ptr<std::string>> send_queue_;
bool write_in_progress_;
};
}; // namespace openarm_mujoco_hardware

View File

@ -0,0 +1,25 @@
<!--
 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.
-->
<library path="openarm_mujoco_hardware">
<class name="openarm_mujoco_hardware/MujocoHardware"
type="openarm_mujoco_hardware::MujocoHardware"
base_class_type="hardware_interface::SystemInterface">
<description>
ros2_control hardware interface.
</description>
</class>
</library>

View File

@ -0,0 +1,39 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<!--
 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.
-->
<package format="3">
<name>openarm_mujoco_hardware</name>
<version>1.0.0</version>
<description>MuJoCo hardware interface for ros2_control</description>
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>nlohmann-json-dev</build_depend>
<depend>rclcpp</depend>
<depend>hardware_interface</depend>
<depend>pluginlib</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ros2_control_test_assets</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@ -0,0 +1,322 @@
// 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.
#include <openarm_mujoco_hardware/openarm_mujoco_hardware.hpp>
namespace openarm_mujoco_hardware {
hardware_interface::CallbackReturn MujocoHardware::on_init(
const hardware_interface::HardwareInfo& info) {
if (hardware_interface::SystemInterface::on_init(info) !=
CallbackReturn::SUCCESS) {
return CallbackReturn::ERROR;
}
if (info.hardware_parameters.find("websocket_port") !=
info.hardware_parameters.end()) {
const double val = std::stoi(info.hardware_parameters.at("websocket_port"));
if (val <= 0) {
return hardware_interface::CallbackReturn::FAILURE;
}
websocket_port_ = val;
} else {
websocket_port_ = kDefaultWebsocketPort;
}
std::cerr << "websocket port: " << websocket_port_ << std::endl;
address_ = boost::asio::ip::make_address("0.0.0.0");
endpoint_ = boost::asio::ip::tcp::endpoint(address_, websocket_port_);
// allocate space for joint states
const size_t DOF = info_.joints.size();
qpos_.resize(DOF, 0.0);
qvel_.resize(DOF, 0.0);
qtau_.resize(DOF, 0.0);
cmd_qpos_.resize(DOF, 0.0);
cmd_qvel_.resize(DOF, 0.0);
cmd_qtau_ff_.resize(DOF, 0.0);
return hardware_interface::CallbackReturn::SUCCESS;
}
void MujocoHardware::start_accept() {
acceptor_.async_accept([this](boost::beast::error_code ec,
boost::asio::ip::tcp::socket socket) {
if (ec) {
std::cerr << "error accepting connection: " << ec.message() << std::endl;
}
std::cout << "new connection accepted." << std::endl;
ws_session_ = WebSocketSession::create(std::move(socket), this);
ws_session_->run();
this->start_accept();
});
}
hardware_interface::CallbackReturn MujocoHardware::on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) {
boost::beast::error_code ec;
if (acceptor_.is_open()) {
return hardware_interface::CallbackReturn::FAILURE;
} else {
acceptor_.open(endpoint_.protocol(), ec);
if (ec) {
throw std::runtime_error("open error: " + ec.message());
}
}
acceptor_.set_option(boost::asio::socket_base::reuse_address(true), ec);
if (ec) {
throw std::runtime_error("enable address reuse error: " + ec.message());
}
acceptor_.bind(endpoint_, ec);
if (ec) {
throw std::runtime_error("bind error: " + ec.message());
}
acceptor_.listen(boost::asio::socket_base::max_listen_connections, ec);
if (ec) {
throw std::runtime_error("listen error: " + ec.message());
}
start_accept();
ioc_thread_ = std::thread([this]() {
try {
ioc_.run();
} catch (const std::exception& e) {
std::cerr << "error in io_context thread: " << e.what() << std::endl;
}
});
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::CallbackReturn MujocoHardware::on_cleanup(
const rclcpp_lifecycle::State& /*previous_state*/) {
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::CallbackReturn MujocoHardware::on_shutdown(
const rclcpp_lifecycle::State& /*previous_state*/) {
clear_cmd_torque();
ioc_.stop();
if (ioc_thread_.joinable()) ioc_thread_.join();
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::CallbackReturn MujocoHardware::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
return hardware_interface::CallbackReturn::SUCCESS;
}
void MujocoHardware::clear_cmd_torque() {
nlohmann::json cmd_msg;
nlohmann::json& cmd = cmd_msg["cmd"];
for (size_t i = 0; i < cmd_qpos_.size(); ++i) {
cmd[info_.joints[i].name] = 0.0;
}
if (ws_session_) {
ws_session_->send_json(cmd_msg);
}
}
hardware_interface::CallbackReturn MujocoHardware::on_deactivate(
const rclcpp_lifecycle::State& /*previous_state*/) {
clear_cmd_torque();
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::CallbackReturn MujocoHardware::on_error(
const rclcpp_lifecycle::State& /*previous_state*/) {
clear_cmd_torque();
return hardware_interface::CallbackReturn::SUCCESS;
}
std::vector<hardware_interface::StateInterface>
MujocoHardware::export_state_interfaces() {
std::vector<hardware_interface::StateInterface> state_interfaces;
for (size_t i = 0; i < qpos_.size(); ++i) {
state_interfaces.emplace_back(hardware_interface::StateInterface(
info_.joints.at(i).name, hardware_interface::HW_IF_POSITION,
&qpos_[i]));
state_interfaces.emplace_back(hardware_interface::StateInterface(
info_.joints.at(i).name, hardware_interface::HW_IF_VELOCITY,
&qvel_[i]));
// state_interfaces.emplace_back(hardware_interface::StateInterface(info_.joints.at(i).name,
// hardware_interface::HW_IF_EFFORT, &qtau_[i]));
}
return state_interfaces;
}
std::vector<hardware_interface::CommandInterface>
MujocoHardware::export_command_interfaces() {
std::vector<hardware_interface::CommandInterface> command_interfaces;
for (size_t i = 0; i < qpos_.size(); ++i) {
command_interfaces.emplace_back(hardware_interface::CommandInterface(
info_.joints.at(i).name, hardware_interface::HW_IF_POSITION,
&cmd_qpos_[i]));
command_interfaces.emplace_back(hardware_interface::CommandInterface(
info_.joints.at(i).name, hardware_interface::HW_IF_VELOCITY,
&cmd_qvel_[i]));
command_interfaces.emplace_back(hardware_interface::CommandInterface(
info_.joints.at(i).name, hardware_interface::HW_IF_EFFORT,
&cmd_qtau_ff_[i]));
}
return command_interfaces;
}
hardware_interface::return_type MujocoHardware::read(
const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
// Read state from the last recieived websocket message
// Why decouple this? The simulation might be paused, and we want to read the
// last state
// right now this is optional as state is updated by listening to messages
// from MuJoCo
return hardware_interface::return_type::OK;
}
hardware_interface::return_type MujocoHardware::write(
const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
// send a websocket message
nlohmann::json cmd_msg;
nlohmann::json& cmd = cmd_msg["cmd"];
for (size_t i = 0; i < cmd_qpos_.size(); ++i) {
const double qpos_error = cmd_qpos_[i] - qpos_[i];
const double qvel_error = cmd_qvel_[i] - qvel_[i];
const double qtau_ff = cmd_qtau_ff_[i];
double cmd_torque = KP_[i] * qpos_error + KD_[i] * qvel_error + qtau_ff;
// if (cmd_torque > MAX_MOTOR_TORQUE) {
// cmd_torque = MAX_MOTOR_TORQUE;
// } else if (cmd_torque < -MAX_MOTOR_TORQUE) {
// cmd_torque = -MAX_MOTOR_TORQUE;
// }
cmd[info_.joints[i].name] = cmd_torque;
}
if (ws_session_) {
ws_session_->send_json(cmd_msg);
} else {
std::cerr << "MuJoCo WebSocket session is not active, please connect at "
<< kMuJoCoWebSocketURL_ << std::endl;
}
return hardware_interface::return_type::OK;
}
WebSocketSession::WebSocketSession(boost::asio::ip::tcp::socket socket,
MujocoHardware* hw)
: ws_(std::move(socket)), hw_(hw), write_in_progress_(false) {}
std::shared_ptr<WebSocketSession> WebSocketSession::create(
boost::asio::ip::tcp::socket socket, MujocoHardware* hw) {
return std::make_shared<WebSocketSession>(std::move(socket), hw);
}
void WebSocketSession::send_json(const nlohmann::json& j) {
std::shared_ptr<std::string> msg = std::make_shared<std::string>(j.dump());
boost::asio::post(ws_.get_executor(), [self = shared_from_this(), msg] {
self->send_queue_.push_back(msg);
if (!self->write_in_progress_) {
self->flush();
}
});
}
void WebSocketSession::flush() {
if (send_queue_.empty()) {
write_in_progress_ = false;
return;
}
write_in_progress_ = true;
auto msg = send_queue_.front();
send_queue_.pop_front();
ws_.async_write(boost::asio::buffer(*msg),
[self = shared_from_this(), msg](boost::beast::error_code ec,
std::size_t) {
if (ec) {
std::cerr << "send error: " << ec.message() << std::endl;
}
self->write_in_progress_ = false;
self->flush();
});
}
void WebSocketSession::run() { do_handshake(); }
void WebSocketSession::do_handshake() {
ws_.set_option(boost::beast::websocket::stream_base::timeout::suggested(
boost::beast::role_type::server));
ws_.async_accept(boost::beast::bind_front_handler(
&WebSocketSession::on_accept, shared_from_this()));
}
void WebSocketSession::on_accept(boost::beast::error_code ec) {
if (ec) {
std::cerr << "handshake failed: " << ec.message() << std::endl;
}
do_read();
}
void WebSocketSession::do_read() {
ws_.async_read(buffer_, boost::beast::bind_front_handler(
&WebSocketSession::on_read, shared_from_this()));
}
void WebSocketSession::on_read(boost::beast::error_code ec,
std::size_t bytes_transferred) {
if (ec) {
std::cerr << "read error: " << ec.message() << std::endl;
return;
}
std::string data = boost::beast::buffers_to_string(buffer_.data());
{
std::lock_guard<std::mutex>(hw_->state_mutex_);
try {
nlohmann::json j = nlohmann::json::parse(data);
// if "state" key exists, update the hardware state
if (j.contains("state")) {
const nlohmann::json& state = j["state"];
for (size_t i = 0; i < hw_->info_.joints.size(); ++i) {
const auto& joint = hw_->info_.joints[i];
if (state.contains(joint.name)) {
const nlohmann::json& joint_data = state.at(joint.name);
if (joint_data.contains("qpos")) {
hw_->qpos_[i] = joint_data.at("qpos").get<double>();
}
if (joint_data.contains("qvel")) {
hw_->qvel_[i] = joint_data.at("qvel").get<double>();
}
}
}
}
} catch (const nlohmann::json::parse_error& e) {
std::cerr << "json parse error: " << e.what() << std::endl;
}
};
buffer_.consume(bytes_transferred);
do_read();
}
}; // namespace openarm_mujoco_hardware
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(openarm_mujoco_hardware::MujocoHardware,
hardware_interface::SystemInterface)

View File

@ -0,0 +1,31 @@
// 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.
#include <gtest/gtest.h>
#include <pluginlib/class_loader.hpp>
#include "hardware_interface/system_interface.hpp"
static constexpr const char* kPluginName =
"openarm_mujoco_hardware/MujocoHardware";
TEST(TestLoadMujocoOpenarmHardware, can_load_plugin) {
pluginlib::ClassLoader<hardware_interface::SystemInterface> loader(
"openarm_mujoco_hardware", "hardware_interface::SystemInterface");
std::shared_ptr<hardware_interface::SystemInterface> instance;
ASSERT_NO_THROW(instance = loader.createSharedInstance(kPluginName));
EXPECT_NE(instance, nullptr);
}