Cleanup bimanual_description

This commit is contained in:
Thomason Zhou 2025-03-11 13:06:46 +09:00
parent 3b8f12da9c
commit 17b99f5342
83 changed files with 546 additions and 3441 deletions

View File

@ -1,7 +1,6 @@
# ROS2 packages for OpenArm robots # ROS2 packages for OpenArm robots
- openarm_description: urdf with gripper actuator - openarm_description: urdf with gripper actuator
- openarm_grip_description: legacy urdf, to be removed shortly
- openarm_moveit_config: motion planning with [moveit2](https://github.com/moveit/moveit2) - openarm_moveit_config: motion planning with [moveit2](https://github.com/moveit/moveit2)
https://github.com/user-attachments/assets/a0f962e5-6150-49ce-b18e-9914bcb322ef https://github.com/user-attachments/assets/a0f962e5-6150-49ce-b18e-9914bcb322ef

View File

@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.8)
project(openarm_two_arms) project(openarm_bimanual_description)
find_package(ament_cmake REQUIRED) find_package(ament_cmake REQUIRED)

View File

@ -0,0 +1,47 @@
from pathlib import Path
import launch
from launch.substitutions import Command
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
import launch_ros
from launch_ros.parameter_descriptions import ParameterValue
def generate_launch_description():
pkg_share = Path(
launch_ros.substitutions.FindPackageShare(package="openarm_bimanual_description").find(
"openarm_bimanual_description"
)
)
default_model_path = pkg_share / "urdf/openarm_bimanual_wrapper.urdf.xacro"
use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument("use_sim_time", default_value="true")
robot_state_publisher_node = launch_ros.actions.Node(
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[
{
# ParameterValue is required to avoid being interpreted as YAML.
"robot_description": ParameterValue(
Command(["xacro ", LaunchConfiguration("model")]), value_type=str
),
"use_sim_time": use_sim_time,
},
],
)
return launch.LaunchDescription(
[
launch.actions.DeclareLaunchArgument(
name="model",
default_value=str(default_model_path),
description="Absolute path to the robot's URDF file",
),
use_sim_time_launch_arg,
robot_state_publisher_node,
]
)

View File

@ -0,0 +1,100 @@
from pathlib import Path
import launch
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
import launch_ros
from launch_ros.substitutions import FindPackageShare
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
pkg_share = Path(
launch_ros.substitutions.FindPackageShare(package="openarm_bimanual_description").find(
"openarm_bimanual_description"
)
)
default_model_path = pkg_share / "urdf/openarm_bimanual_wrapper.urdf.xacro"
default_rviz_config_path = pkg_share / "rviz/robot_description.rviz"
use_sim_time = LaunchConfiguration("use_sim_time")
robot_state_publisher_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("openarm_bimanual_description"),
"launch",
"description.launch.py",
]
),
]
),
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
joint_state_publisher_node = launch_ros.actions.Node(
package="joint_state_publisher",
executable="joint_state_publisher",
name="joint_state_publisher",
condition=launch.conditions.UnlessCondition(LaunchConfiguration("gui")),
parameters=[
{
"use_sim_time": use_sim_time,
}
],
)
joint_state_publisher_gui_node = launch_ros.actions.Node(
package="joint_state_publisher_gui",
executable="joint_state_publisher_gui",
name="joint_state_publisher_gui",
condition=launch.conditions.IfCondition(LaunchConfiguration("gui")),
parameters=[
{
"use_sim_time": use_sim_time,
}
],
)
rviz_node = launch_ros.actions.Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="screen",
arguments=["-d", LaunchConfiguration("rvizconfig")],
parameters=[
{
"use_sim_time": use_sim_time,
}
],
)
return launch.LaunchDescription(
[
launch.actions.DeclareLaunchArgument(
name="use_sim_time",
default_value="false",
description="Flag to enable usage of simulation time",
),
launch.actions.DeclareLaunchArgument(
name="gui",
default_value="True",
description="Flag to enable joint_state_publisher_gui",
),
launch.actions.DeclareLaunchArgument(
name="model",
default_value=str(default_model_path),
description="Absolute path to robot urdf file",
),
launch.actions.DeclareLaunchArgument(
name="rvizconfig",
default_value=str(default_rviz_config_path),
description="Absolute path to rviz config file",
),
joint_state_publisher_node,
joint_state_publisher_gui_node,
robot_state_publisher_node,
rviz_node,
]
)

View File

@ -15,9 +15,13 @@ def get_package_file(package, file_path):
def generate_launch_description(): def generate_launch_description():
xacro_file = get_package_file("openarm_two_arms", "urdf/openarm_two_arms.urdf.xacro") xacro_file = get_package_file(
"openarm_bimanual_description", "urdf/openarm_bimanual.urdf.xacro"
)
urdf = xacro.process_file(xacro_file).toprettyxml(indent=" ") urdf = xacro.process_file(xacro_file).toprettyxml(indent=" ")
default_rviz_config_path = get_package_file("openarm_two_arms", "rviz/robot_description.rviz") default_rviz_config_path = get_package_file(
"openarm_bimanual_description", "rviz/robot_description.rviz"
)
return launch.LaunchDescription( return launch.LaunchDescription(
[ [

View File

@ -0,0 +1,149 @@
import os
import re
import subprocess
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
resources_package = "openarm_bimanual_description"
# Make path to resources dir without last package_name fragment.
path_to_share_dir_clipped = "".join(
get_package_share_directory(resources_package).rsplit("/" + resources_package, 1)
)
# Gazebo hint for resources.
os.environ["GZ_SIM_RESOURCE_PATH"] = path_to_share_dir_clipped
# Ensure `SDF_PATH` is populated since `sdformat_urdf` uses this rather
# than `GZ_SIM_RESOURCE_PATH` to locate resources.
if "GZ_SIM_RESOURCE_PATH" in os.environ:
gz_sim_resource_path = os.environ["GZ_SIM_RESOURCE_PATH"]
if "SDF_PATH" in os.environ:
sdf_path = os.environ["SDF_PATH"]
os.environ["SDF_PATH"] = sdf_path + ":" + gz_sim_resource_path
else:
os.environ["SDF_PATH"] = gz_sim_resource_path
use_custom_world = LaunchConfiguration("use_custom_world")
use_custom_world_launch_arg = DeclareLaunchArgument("use_custom_world", default_value="true")
gazebo_world = LaunchConfiguration("gazebo_world")
gazebo_world_launch_arg = DeclareLaunchArgument("gazebo_world", default_value="empty.sdf")
# prepare custom world
world = os.getenv("GZ_SIM_WORLD", "empty")
fly_world_path = resources_package + "/worlds/" + world + ".sdf"
gz_version = subprocess.getoutput("gz sim --versions")
gz_version_major = re.search(r"^\d{1}", gz_version).group()
launch_arguments = dict(
gz_args="-r " + str(fly_world_path) + " --verbose ", gz_version=gz_version_major
).items()
# Gazebo Sim.
# by default the custom world is used, otherwise the gazebo world is used, which can be changed with the argument
pkg_ros_gz_sim = get_package_share_directory("ros_gz_sim")
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_ros_gz_sim, "launch", "gz_sim.launch.py"),
),
launch_arguments=launch_arguments
if use_custom_world
else dict(gz_args="-r " + gazebo_world + " --verbose").items(),
)
# Spawn
spawn = Node(
package="ros_gz_sim",
executable="create",
arguments=[
"-name",
"openarm_bimanual_description",
"-x",
"1.2",
"-z",
"2.3",
"-Y",
"3.4",
"-topic",
"/robot_description",
],
output="screen",
)
use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument("use_sim_time", default_value="true")
use_rviz = LaunchConfiguration("use_rviz")
use_rviz_arg = DeclareLaunchArgument("use_rviz", default_value="true")
robot_state_publisher = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare(resources_package),
"launch",
"description.launch.py",
]
),
]
),
condition=UnlessCondition(use_rviz), # rviz launch includes rsp.
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
rviz = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare(resources_package),
"launch",
"display.launch.py",
]
),
]
),
condition=IfCondition(use_rviz),
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
gz_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=["/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock"],
output="screen",
parameters=[
{
"use_sim_time": use_sim_time,
}
],
)
return LaunchDescription(
[
use_sim_time_launch_arg,
use_rviz_arg,
use_custom_world_launch_arg,
gazebo_world_launch_arg,
robot_state_publisher,
rviz,
gazebo,
spawn,
gz_bridge,
]
)

View File

@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3"> <package format="3">
<name>openarm_two_arms</name> <name>openarm_bimanual_description</name>
<version>0.0.0</version> <version>0.0.0</version>
<description>TODO: Package description</description> <description>TODO: Package description</description>
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer> <maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>

View File

@ -5,8 +5,6 @@
<material name="gray"> <material name="gray">
<color rgba="${105/255} ${105/255} ${105/255} 1.0"/> <color rgba="${105/255} ${105/255} ${105/255} 1.0"/>
</material> </material>
<!-- <xacro:property name="zero_pos" value="vertical"/> -->
<xacro:macro name="openarm" params="side prefix"> <xacro:macro name="openarm" params="side prefix">
<xacro:property name="reflect" value="${1 if side=='right' else -1}"/> <xacro:property name="reflect" value="${1 if side=='right' else -1}"/>
@ -16,7 +14,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/> <origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link1.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link1.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -36,7 +34,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/> <origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link2.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link2.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -56,7 +54,7 @@
<visual> <visual>
<origin rpy="${pi * 0.5} 0 0" xyz="0.0 0.0987 0.02975"/> <origin rpy="${pi * 0.5} 0 0" xyz="0.0 0.0987 0.02975"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link3.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link3.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -76,7 +74,7 @@
<visual> <visual>
<origin rpy="${pi} -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/> <origin rpy="${pi} -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link4.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link4.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -96,7 +94,7 @@
<visual> <visual>
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/> <origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link5.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link5.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -116,7 +114,7 @@
<visual> <visual>
<origin rpy="${-2.1276679791326423*reflect + rotate} ${reflect* -1.5542266826921929} ${rotate}" xyz="${reflect*-0.0485412 + (0 if side=='right' else 0.012)} ${reflect*-0.0860404 +(0 if side=='right' else 0.0018)} ${0.437784- (0 if side=='right' else 0.0023)}"/> <origin rpy="${-2.1276679791326423*reflect + rotate} ${reflect* -1.5542266826921929} ${rotate}" xyz="${reflect*-0.0485412 + (0 if side=='right' else 0.012)} ${reflect*-0.0860404 +(0 if side=='right' else 0.0018)} ${0.437784- (0 if side=='right' else 0.0023)}"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/${'link6_rightarm.stl' if side=='right' else 'link6_leftarm.stl'}"/> <mesh filename="package://openarm_bimanual_description/meshes/${'link6_rightarm.stl' if side=='right' else 'link6_leftarm.stl'}"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -136,7 +134,7 @@
<visual> <visual>
<origin rpy="0 ${reflect*-0.008758182894510852 + rotate} 0" xyz="0.558839 ${reflect*-0.00358671 + (0 if side=='right' else -0.007)} ${reflect*-0.0631962 + (0 if side=='right' else 0.071)}"/> <origin rpy="0 ${reflect*-0.008758182894510852 + rotate} 0" xyz="0.558839 ${reflect*-0.00358671 + (0 if side=='right' else -0.007)} ${reflect*-0.0631962 + (0 if side=='right' else 0.071)}"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/${'link7_rightarm.stl' if side=='right' else 'link7_leftarm.stl'}"/> <mesh filename="package://openarm_bimanual_description/meshes/${'link7_rightarm.stl' if side=='right' else 'link7_leftarm.stl'}"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -156,7 +154,7 @@
<visual> <visual>
<origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/> <origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link8.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link8.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -176,14 +174,14 @@
<visual> <visual>
<origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/> <origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/left_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/left_jaw.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/> <origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/left_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/left_jaw.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <inertial>
@ -196,14 +194,14 @@
<visual> <visual>
<origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/> <origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/right_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/right_jaw.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/> <origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/right_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/right_jaw.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <inertial>

View File

@ -1,9 +1,9 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from openarm_two_arms.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 | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<robot name="openarm_two_arms"> <robot name="openarm_bimanual">
<link name="world"/> <link name="world"/>
<material name="gray"> <material name="gray">
<color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/> <color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/>
@ -13,7 +13,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/pedestal_link.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/pedestal_link.stl"/>
</geometry> </geometry>
<material name="gray"> <material name="gray">
<color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/> <color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/>
@ -35,7 +35,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/> <origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link1.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link1.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -55,7 +55,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/> <origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link2.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link2.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -75,7 +75,7 @@
<visual> <visual>
<origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0987 0.02975"/> <origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0987 0.02975"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link3.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link3.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -95,7 +95,7 @@
<visual> <visual>
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/> <origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link4.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link4.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -115,7 +115,7 @@
<visual> <visual>
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/> <origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link5.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link5.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -135,7 +135,7 @@
<visual> <visual>
<origin rpy="-2.1276679791326423 -1.5542266826921929 0" xyz="-0.0485412 -0.0860404 0.437784"/> <origin rpy="-2.1276679791326423 -1.5542266826921929 0" xyz="-0.0485412 -0.0860404 0.437784"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link6_rightarm.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link6_rightarm.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -155,7 +155,7 @@
<visual> <visual>
<origin rpy="0 -0.008758182894510852 0" xyz="0.558839 -0.00358671 -0.0631962"/> <origin rpy="0 -0.008758182894510852 0" xyz="0.558839 -0.00358671 -0.0631962"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link7_rightarm.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link7_rightarm.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -175,7 +175,7 @@
<visual> <visual>
<origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/> <origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link8.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link8.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -195,14 +195,14 @@
<visual> <visual>
<origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/> <origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/left_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/left_jaw.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/> <origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/left_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/left_jaw.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <inertial>
@ -215,14 +215,14 @@
<visual> <visual>
<origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/> <origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/right_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/right_jaw.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/> <origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/right_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/right_jaw.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <inertial>
@ -299,7 +299,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/> <origin rpy="0 0 0" xyz="0.0 0.0 -0.0007"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link1.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link1.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -319,7 +319,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/> <origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link2.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link2.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -339,7 +339,7 @@
<visual> <visual>
<origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0987 0.02975"/> <origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0987 0.02975"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link3.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link3.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -359,7 +359,7 @@
<visual> <visual>
<origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/> <origin rpy="3.141592653589793 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link4.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link4.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -379,7 +379,7 @@
<visual> <visual>
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/> <origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link5.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link5.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -399,7 +399,7 @@
<visual> <visual>
<origin rpy="5.269260632722435 1.5542266826921929 3.141592653589793" xyz="0.0605412 0.0878404 0.435484"/> <origin rpy="5.269260632722435 1.5542266826921929 3.141592653589793" xyz="0.0605412 0.0878404 0.435484"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link6_leftarm.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link6_leftarm.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -419,7 +419,7 @@
<visual> <visual>
<origin rpy="0 3.150350836484304 0" xyz="0.558839 -0.0034132900000000002 0.1341962"/> <origin rpy="0 3.150350836484304 0" xyz="0.558839 -0.0034132900000000002 0.1341962"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link7_leftarm.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link7_leftarm.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -439,7 +439,7 @@
<visual> <visual>
<origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/> <origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/link8.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/link8.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
@ -459,14 +459,14 @@
<visual> <visual>
<origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/> <origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/left_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/left_jaw.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/> <origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/left_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/left_jaw.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <inertial>
@ -479,14 +479,14 @@
<visual> <visual>
<origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/> <origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/right_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/right_jaw.stl"/>
</geometry> </geometry>
<material name="gray"/> <material name="gray"/>
</visual> </visual>
<collision> <collision>
<origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/> <origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/right_jaw.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/right_jaw.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <inertial>

View File

@ -1,9 +1,9 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_two_arms"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<link name="world"/> <link name="world"/>
<xacro:include filename="openarm.xacro"/> <xacro:include filename="openarm.xacro"/>
<xacro:include filename="openarm_two_arms_pedestal.urdf"/> <xacro:include filename="openarm_pedestal.urdf"/>
<xacro:openarm prefix="right_" side="right"/> <xacro:openarm prefix="right_" side="right"/>
<xacro:openarm prefix="left_" side="left"/> <xacro:openarm prefix="left_" side="left"/>

View File

@ -0,0 +1,5 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:include filename="openarm_bimanual.urdf.xacro"/>
<xacro:include filename="openarm_bimanual_sensors.urdf.xacro"/>
</robot>

View File

@ -1,10 +1,10 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<robot name="openarm_two_arms"> <robot name="openarm_bimanual_description">
<link name="pedestal_link"> <link name="pedestal_link">
<visual> <visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/pedestal_link.stl"/> <mesh filename="package://openarm_bimanual_description/meshes/pedestal_link.stl"/>
</geometry> </geometry>
<material name="gray"> <material name="gray">
<color rgba="${105/255} ${105/255} ${105/255} 1.0"/> <color rgba="${105/255} ${105/255} ${105/255} 1.0"/>

View File

@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.8)
project(openarm_description_2) project(openarm_description)
find_package(ament_cmake REQUIRED) find_package(ament_cmake REQUIRED)

View File

@ -10,30 +10,38 @@ from launch_ros.parameter_descriptions import ParameterValue
def generate_launch_description(): def generate_launch_description():
pkg_share = Path(launch_ros.substitutions.FindPackageShare(package='openarm_description_2').find('openarm_description_2')) pkg_share = Path(
default_model_path = pkg_share / 'urdf/openarm_wrapper.urdf.xacro' launch_ros.substitutions.FindPackageShare(package="openarm_description").find(
"openarm_description"
)
)
default_model_path = pkg_share / "urdf/openarm_wrapper.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', default_value='true') use_sim_time_launch_arg = DeclareLaunchArgument("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",
executable='robot_state_publisher', executable="robot_state_publisher",
parameters=[ parameters=[
{ {
# ParameterValue is required to avoid being interpreted as YAML. # ParameterValue is required to avoid being interpreted as YAML.
'robot_description': ParameterValue(Command(['xacro ', LaunchConfiguration('model')]), value_type=str), "robot_description": ParameterValue(
'use_sim_time': use_sim_time, Command(["xacro ", LaunchConfiguration("model")]), value_type=str
),
"use_sim_time": use_sim_time,
}, },
], ],
) )
return launch.LaunchDescription([ return launch.LaunchDescription(
launch.actions.DeclareLaunchArgument( [
name='model', launch.actions.DeclareLaunchArgument(
default_value=str(default_model_path), name="model",
description="Absolute path to the robot's URDF file", default_value=str(default_model_path),
), description="Absolute path to the robot's URDF file",
use_sim_time_launch_arg, ),
robot_state_publisher_node, use_sim_time_launch_arg,
]) robot_state_publisher_node,
]
)

View File

@ -10,75 +10,91 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description(): def generate_launch_description():
pkg_share = Path(launch_ros.substitutions.FindPackageShare(package='openarm_description_2').find('openarm_description_2')) pkg_share = Path(
default_model_path = pkg_share / 'urdf/openarm_wrapper.urdf.xacro' launch_ros.substitutions.FindPackageShare(package="openarm_description").find(
default_rviz_config_path = pkg_share / 'rviz/robot_description.rviz' "openarm_description"
)
)
default_model_path = pkg_share / "urdf/openarm_wrapper.urdf.xacro"
default_rviz_config_path = pkg_share / "rviz/robot_description.rviz"
use_sim_time = LaunchConfiguration('use_sim_time') use_sim_time = LaunchConfiguration("use_sim_time")
robot_state_publisher_node = IncludeLaunchDescription( robot_state_publisher_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([ PythonLaunchDescriptionSource(
PathJoinSubstitution([ [
FindPackageShare('openarm_description_2'), PathJoinSubstitution(
'launch', [
'description.launch.py', FindPackageShare("openarm_description"),
]), "launch",
]), "description.launch.py",
]
),
]
),
launch_arguments=dict(use_sim_time=use_sim_time).items(), launch_arguments=dict(use_sim_time=use_sim_time).items(),
) )
joint_state_publisher_node = launch_ros.actions.Node( joint_state_publisher_node = launch_ros.actions.Node(
package='joint_state_publisher', package="joint_state_publisher",
executable='joint_state_publisher', executable="joint_state_publisher",
name='joint_state_publisher', name="joint_state_publisher",
condition=launch.conditions.UnlessCondition(LaunchConfiguration('gui')), condition=launch.conditions.UnlessCondition(LaunchConfiguration("gui")),
parameters=[{ parameters=[
'use_sim_time': use_sim_time, {
}], "use_sim_time": use_sim_time,
}
],
) )
joint_state_publisher_gui_node = launch_ros.actions.Node( joint_state_publisher_gui_node = launch_ros.actions.Node(
package='joint_state_publisher_gui', package="joint_state_publisher_gui",
executable='joint_state_publisher_gui', executable="joint_state_publisher_gui",
name='joint_state_publisher_gui', name="joint_state_publisher_gui",
condition=launch.conditions.IfCondition(LaunchConfiguration('gui')), condition=launch.conditions.IfCondition(LaunchConfiguration("gui")),
parameters=[{ parameters=[
'use_sim_time': use_sim_time, {
}], "use_sim_time": use_sim_time,
}
],
) )
rviz_node = launch_ros.actions.Node( rviz_node = launch_ros.actions.Node(
package='rviz2', package="rviz2",
executable='rviz2', executable="rviz2",
name='rviz2', name="rviz2",
output='screen', output="screen",
arguments=['-d', LaunchConfiguration('rvizconfig')], arguments=["-d", LaunchConfiguration("rvizconfig")],
parameters=[{ parameters=[
'use_sim_time': use_sim_time, {
}], "use_sim_time": use_sim_time,
}
],
) )
return launch.LaunchDescription([ return launch.LaunchDescription(
launch.actions.DeclareLaunchArgument( [
name='use_sim_time', launch.actions.DeclareLaunchArgument(
default_value='false', name="use_sim_time",
description='Flag to enable usage of simulation time', default_value="false",
), description="Flag to enable usage of simulation time",
launch.actions.DeclareLaunchArgument( ),
name='gui', launch.actions.DeclareLaunchArgument(
default_value='True', name="gui",
description='Flag to enable joint_state_publisher_gui', default_value="True",
), description="Flag to enable joint_state_publisher_gui",
launch.actions.DeclareLaunchArgument( ),
name='model', launch.actions.DeclareLaunchArgument(
default_value=str(default_model_path), name="model",
description='Absolute path to robot urdf file', default_value=str(default_model_path),
), description="Absolute path to robot urdf file",
launch.actions.DeclareLaunchArgument( ),
name='rvizconfig', launch.actions.DeclareLaunchArgument(
default_value=str(default_rviz_config_path), name="rvizconfig",
description='Absolute path to rviz config file', default_value=str(default_rviz_config_path),
), description="Absolute path to rviz config file",
joint_state_publisher_node, ),
joint_state_publisher_gui_node, joint_state_publisher_node,
robot_state_publisher_node, joint_state_publisher_gui_node,
rviz_node, robot_state_publisher_node,
]) rviz_node,
]
)

View File

@ -18,14 +18,15 @@ from launch_ros.substitutions import FindPackageShare
def generate_launch_description(): def generate_launch_description():
resources_package = "openarm_description"
resources_package = 'openarm_description_2'
# 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(get_package_share_directory(resources_package).rsplit('/' + resources_package, 1)) path_to_share_dir_clipped = "".join(
get_package_share_directory(resources_package).rsplit("/" + resources_package, 1)
)
# Gazebo hint for resources. # Gazebo hint for resources.
os.environ['GZ_SIM_RESOURCE_PATH'] = path_to_share_dir_clipped os.environ["GZ_SIM_RESOURCE_PATH"] = path_to_share_dir_clipped
# Ensure `SDF_PATH` is populated since `sdformat_urdf` uses this rather # Ensure `SDF_PATH` is populated since `sdformat_urdf` uses this rather
@ -39,90 +40,110 @@ def generate_launch_description():
else: else:
os.environ["SDF_PATH"] = gz_sim_resource_path os.environ["SDF_PATH"] = gz_sim_resource_path
use_custom_world = LaunchConfiguration("use_custom_world")
use_custom_world = LaunchConfiguration('use_custom_world') use_custom_world_launch_arg = DeclareLaunchArgument("use_custom_world", default_value="true")
use_custom_world_launch_arg = DeclareLaunchArgument('use_custom_world', default_value='true') gazebo_world = LaunchConfiguration("gazebo_world")
gazebo_world = LaunchConfiguration('gazebo_world') gazebo_world_launch_arg = DeclareLaunchArgument("gazebo_world", default_value="empty.sdf")
gazebo_world_launch_arg = DeclareLaunchArgument('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")
fly_world_path = resources_package + '/worlds/' + world + '.sdf' fly_world_path = resources_package + "/worlds/" + world + ".sdf"
gz_version = subprocess.getoutput("gz sim --versions") gz_version = subprocess.getoutput("gz sim --versions")
gz_version_major = re.search(r'^\d{1}', gz_version).group() gz_version_major = re.search(r"^\d{1}", gz_version).group()
launch_arguments=dict(gz_args = '-r ' + str(fly_world_path) + ' --verbose ', gz_version = gz_version_major).items() launch_arguments = dict(
gz_args="-r " + str(fly_world_path) + " --verbose ", gz_version=gz_version_major
).items()
# Gazebo Sim. # Gazebo Sim.
# by default the custom world is used, otherwise the gazebo world is used, which can be changed with the argument # by default the custom world is used, otherwise the gazebo world is used, which can be changed with the argument
pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') pkg_ros_gz_sim = get_package_share_directory("ros_gz_sim")
gazebo = IncludeLaunchDescription( gazebo = IncludeLaunchDescription(
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 if use_custom_world else dict(gz_args='-r ' + gazebo_world + ' --verbose').items(), launch_arguments=launch_arguments
if use_custom_world
else dict(gz_args="-r " + gazebo_world + " --verbose").items(),
) )
# Spawn # Spawn
spawn = Node( spawn = Node(
package='ros_gz_sim', package="ros_gz_sim",
executable='create', executable="create",
arguments=[ arguments=[
'-name', 'openarm', "-name",
'-x', '1.2', "openarm",
'-z', '2.3', "-x",
'-Y', '3.4', "1.2",
'-topic', '/robot_description', "-z",
], "2.3",
output='screen', "-Y",
"3.4",
"-topic",
"/robot_description",
],
output="screen",
) )
use_sim_time = LaunchConfiguration('use_sim_time') use_sim_time = LaunchConfiguration("use_sim_time")
use_sim_time_launch_arg = DeclareLaunchArgument('use_sim_time', default_value='true') use_sim_time_launch_arg = DeclareLaunchArgument("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")
robot_state_publisher = IncludeLaunchDescription( robot_state_publisher = IncludeLaunchDescription(
PythonLaunchDescriptionSource([ PythonLaunchDescriptionSource(
PathJoinSubstitution([ [
FindPackageShare(resources_package), PathJoinSubstitution(
'launch', [
'description.launch.py', FindPackageShare(resources_package),
]), "launch",
]), "description.launch.py",
condition=UnlessCondition(use_rviz), # rviz launch includes rsp. ]
launch_arguments=dict(use_sim_time=use_sim_time).items(), ),
]
),
condition=UnlessCondition(use_rviz), # rviz launch includes rsp.
launch_arguments=dict(use_sim_time=use_sim_time).items(),
) )
rviz = IncludeLaunchDescription( rviz = IncludeLaunchDescription(
PythonLaunchDescriptionSource([ PythonLaunchDescriptionSource(
PathJoinSubstitution([ [
FindPackageShare(resources_package), PathJoinSubstitution(
'launch', [
'display.launch.py', FindPackageShare(resources_package),
]), "launch",
]), "display.launch.py",
]
),
]
),
condition=IfCondition(use_rviz), condition=IfCondition(use_rviz),
launch_arguments=dict(use_sim_time=use_sim_time).items(), launch_arguments=dict(use_sim_time=use_sim_time).items(),
) )
gz_bridge = Node( gz_bridge = Node(
package='ros_gz_bridge', package="ros_gz_bridge",
executable='parameter_bridge', executable="parameter_bridge",
arguments=['/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock'], arguments=["/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock"],
output='screen', output="screen",
parameters=[{ parameters=[
'use_sim_time': use_sim_time, {
}], "use_sim_time": use_sim_time,
}
],
) )
return LaunchDescription([ return LaunchDescription(
use_sim_time_launch_arg, [
use_rviz_arg, use_sim_time_launch_arg,
use_custom_world_launch_arg, use_rviz_arg,
gazebo_world_launch_arg, use_custom_world_launch_arg,
robot_state_publisher, gazebo_world_launch_arg,
rviz, robot_state_publisher,
gazebo, rviz,
spawn, gazebo,
gz_bridge, spawn,
]) gz_bridge,
]
)

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3"> <package format="3">
<name>openarm_description_2</name> <name>openarm_description</name>
<version>0.0.0</version> <version>0.0.0</version>
<description>TODO: Package description</description> <description>TODO: Package description</description>
<maintainer email="TODO@todo.com">TODO</maintainer> <maintainer email="TODO@todo.com">TODO</maintainer>

View File

@ -1,278 +0,0 @@
<?xml version="1.0" ?>
<robot name="openarm">
<!--Generated by RobotCAD, a ROS Workbench for FreeCAD (https://github.com/drfenixion/freecad.robotcad)-->
<link name="l_J1_v002">
<visual>
<!--J1 v002/Part__Feature.-->
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j1v1_aooobi.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J1_v002__col_J1_v1__BoundBox/col_J1_v1__BoundBox.-->
<origin rpy="0 0 0" xyz="0.0 0.0 0.0296"/>
<geometry>
<box size="0.11 0.073 0.0592"/>
</geometry>
</collision>
<inertial>
<mass value="0.5769283920617252"/>
<origin rpy="0 0 0" xyz="0.0 2.52845e-05 0.0236621"/>
<inertia ixx="0.0003403516757406" ixy="-0.0" ixz="-0.0" iyy="0.000430005830001" iyz="-5.098294821e-07" izz="0.0004802171432002"/>
</inertial>
</link>
<link name="l_J2_v002">
<visual>
<!--J2 v002/Part__Feature001.-->
<origin rpy="0 0 0" xyz="0.0 0.0 -0.05395"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j2v1_jhlkho.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J2_v002__col_J2_v1__BoundBox/col_J2_v1__BoundBox.-->
<origin rpy="0 0 0" xyz="0.0 0.0 0.0371236"/>
<geometry>
<box size="0.059000000014901216 0.08200000000000003 0.0742471498637348"/>
</geometry>
</collision>
<inertial>
<mass value="0.1625750413491735"/>
<origin rpy="0 0 0" xyz="-0.000225878 -0.00183836 0.0278368"/>
<inertia ixx="0.0002390311021329" ixy="-7.55169292e-08" ixz="-1.1282723362e-06" iyy="0.0001049079831478" iyz="5.907962784e-06" izz="0.0001973736868594"/>
</inertial>
</link>
<link name="l_J3_v003">
<visual>
<!--J3 v003/Part__Feature002.-->
<origin rpy="1.570796326794897 0 0" xyz="0.0 0.0987 0.02975"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j3v2_wvlhxy.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J3_v003__col_J3_v2__BoundBox/col_J3_v2__BoundBox.-->
<origin rpy="1.5707963267948968 0 0" xyz="-0.0164466 -0.00045542 0.02975"/>
<geometry>
<box size="0.08989101803441883 0.06999999999999984 0.05903276947803012"/>
</geometry>
</collision>
<inertial>
<mass value="0.420167646991003"/>
<origin rpy="1.5707963267948968 0 0" xyz="-0.00688022 0.0 0.0282752"/>
<inertia ixx="0.0002025600112623" ixy="6.0042478753e-06" ixz="1.3304903058e-06" iyy="0.0002970624991388" iyz="5.980157766e-07" izz="0.0003288999435124"/>
</inertial>
</link>
<link name="l_J4_v002">
<visual>
<!--J4 v002/Part__Feature003.-->
<origin rpy="1.5707963267958094 -1.5620381439005735 0" xyz="0.000536411 0.0992364 0.0612453"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j4v1_augius.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J4_v002__col_J4_v1__BoundBox/col_J4_v1__BoundBox.-->
<origin rpy="1.5707963267958094 -1.5620381439005735 0" xyz="-0.013725 -0.00142762 -0.132481"/>
<geometry>
<box size="0.27584673777150337 0.08211429171582063 0.07186573179325861"/>
</geometry>
</collision>
<inertial>
<mass value="0.8194755393734474"/>
<origin rpy="1.5707963267958094 -1.5620381439005735 0" xyz="-0.00310558 -0.00194096 -0.132377"/>
<inertia ixx="0.0004407845203398" ixy="6.02002369404e-05" ixz="0.0001463745926194" iyy="0.0092087914805304" iyz="1.5469710436e-06" izz="0.0091705393160237"/>
</inertial>
</link>
<link name="l_J5_v003">
<visual>
<!--J5 v003/Part__Feature004.-->
<origin rpy="0 -0.00875818289428989 0" xyz="0.303864 0.0 -0.128451"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j5v2_1zjcxf.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J5_v003__col_J5_v2__BoundBox/col_J5_v2__BoundBox.-->
<origin rpy="0 -0.0087581828942894 0" xyz="-0.0542814 0.00265291 -0.0302022"/>
<geometry>
<box size="0.16827213220625822 0.06430555048399172 0.08257859967140947"/>
</geometry>
</collision>
<inertial>
<mass value="0.4086748254352304"/>
<origin rpy="0 -0.0087581828942894 0" xyz="-0.0831891 0.00251789 -0.0290107"/>
<inertia ixx="0.000314171574253" ixy="-1.13915660296e-05" ixz="-1.88347409006e-05" iyy="0.001221711435314" iyz="1.4672541842e-06" izz="0.0010755135067661"/>
</inertial>
</link>
<link name="l_J6_v002">
<visual>
<!--J6 v002/Part__Feature005.-->
<origin rpy="-2.1276679791304027 -1.5542266826921316 0" xyz="-0.0485412 -0.0860404 0.437784"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j6v1_71vz7n.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J6_v002__col_J6_v1__BoundBox/col_J6_v1__BoundBox.-->
<origin rpy="-2.1276679791303965 -1.5542266826921314 0" xyz="-0.00260794 -0.00312921 -0.0652641"/>
<geometry>
<box size="0.13114353004704765 0.05953478325301745 0.08817196195081879"/>
</geometry>
</collision>
<inertial>
<mass value="0.344847195804925"/>
<origin rpy="-2.1276679791303965 -1.5542266826921314 0" xyz="-0.00898536 -0.0135065 -0.0438611"/>
<inertia ixx="0.0001935598099975" ixy="-1.0061665815e-06" ixz="-3.9096495715e-05" iyy="0.0003486912031866" iyz="6.0880603153e-06" izz="0.0002877497515376"/>
</inertial>
</link>
<link name="l_J7_v002">
<visual>
<!--J7 v002/Part__Feature006.-->
<origin rpy="0 -0.008758182894492011 0" xyz="0.558839 -0.00358671 -0.0631962"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j7v1_ebpnbv.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J7_v002__col_J7_v1__BoundBox/col_J7_v1__BoundBox.-->
<origin rpy="0 -0.008758182894492202 0" xyz="-0.000318103 0.0022839 0.0340014"/>
<geometry>
<box size="0.058327402175132874 0.04432916698753661 0.08267601622411752"/>
</geometry>
</collision>
<inertial>
<mass value="0.2782138078738053"/>
<origin rpy="0 -0.008758182894492202 0" xyz="5.99432e-05 0.0041433 0.0354274"/>
<inertia ixx="0.0001042415331565" ixy="2.735265832e-07" ixz="-1.066232238e-07" iyy="0.0001231355074328" iyz="-8.60499675e-08" izz="9.22131995851e-05"/>
</inertial>
</link>
<link name="l_J8_v002">
<visual>
<!--J8 v002/Part__Feature007.-->
<origin rpy="1.5709195259578743 -0.014065461951076396 0" xyz="0.557948 0.103587 0.019724"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_j8v1_n9o5e8.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_J8_v002__col_J8_v1__BoundBox/col_J8_v1__BoundBox.-->
<origin rpy="1.5709195259578743 -0.014065461951076389 0" xyz="-0.042694 -0.000543176 0.0110286"/>
<geometry>
<box size="0.13038799671743653 0.05180887692688924 0.1601236763440867"/>
</geometry>
</collision>
<inertial>
<mass value="0.3126145274380216"/>
<origin rpy="1.5709195259578743 -0.014065461951076387 0" xyz="-0.0607602 -0.000341696 0.00876618"/>
<inertia ixx="0.0002346566136679" ixy="7.60904888201e-05" ixz="3.088694121e-07" iyy="0.0005065459365215" iyz="1.902281803e-07" izz="0.0003737029250058"/>
</inertial>
</link>
<link name="l_right_jaw_v002">
<visual>
<!--right_jaw v002/Part__Feature009.-->
<origin rpy="0 -0.008758182894796506 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_right_jawv1_fr5g7k.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_right_jaw_v002__col_right_jaw_v1_col_obj/col_right_jaw_v1_col_obj.-->
<origin rpy="0 -0.008758182894796357 0" xyz="0.665265 -0.00286677 -0.175928"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_col_right_jaw_v1_col_obj_p8alje.dae"/>
</geometry>
</collision>
<inertial>
<mass value="0.0429816653011345"/>
<origin rpy="0 -0.008758182894796502 0" xyz="-0.0187844 -0.00272415 -0.0159503"/>
<inertia ixx="1.15612930876e-05" ixy="2.537718468e-06" ixz="-3.6591812258e-06" iyy="2.37016552787e-05" iyz="4.848038236e-07" izz="3.03965294654e-05"/>
</inertial>
</link>
<link name="l_left_jaw_v002">
<visual>
<!--left_jaw v002/Part__Feature008.-->
<origin rpy="0 -0.008758182894441503 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_left_jawv1_mtevtw.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__l_left_jaw_v002__col_left_jaw_v1_col_obj/col_left_jaw_v1_col_obj.-->
<origin rpy="0 -0.008758182894441503 0" xyz="0.665265 -0.00286677 -0.0209282"/>
<geometry>
<mesh filename="package://openarm_description_2/meshes/robotcad_openarm_123_col_left_jaw_v1_col_obj_u5blmp.dae"/>
</geometry>
</collision>
<inertial>
<mass value="0.0429789785639494"/>
<origin rpy="0 -0.008758182894441498 0" xyz="-0.0187138 0.00217075 0.0159499"/>
<inertia ixx="1.17717687429e-05" ixy="-2.3899281666e-06" ixz="3.9992922045e-06" iyy="2.38373544808e-05" iyz="3.494431877e-07" izz="3.04745902141e-05"/>
</inertial>
</link>
<joint name="rev1" type="revolute">
<parent link="l_J1_v002"/>
<child link="l_J2_v002"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.05395"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.356194490192345" upper="2.356194490192345" velocity="0.0"/>
</joint>
<joint name="rev2" type="revolute">
<parent link="l_J2_v002"/>
<child link="l_J3_v003"/>
<origin rpy="-1.5707963267948977 1.5707963267948957 0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
</joint>
<joint name="rev3" type="revolute">
<parent link="l_J3_v003"/>
<child link="l_J4_v002"/>
<origin rpy="1.5707963267949046 0 1.5795545096892487" xyz="-0.0612477 -0.000536432 0.02975"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
<joint name="rev4" type="revolute">
<parent link="l_J4_v002"/>
<child link="l_J5_v003"/>
<origin rpy="0.7854173400827703 -1.5584104649378014 0.7854173400871975" xyz="-0.0021149 -0.0318708 -0.241471"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-0.3490658503988659" upper="2.792526803190927" velocity="0.0"/>
</joint>
<joint name="rev5" type="revolute">
<parent link="l_J5_v003"/>
<child link="l_J6_v002"/>
<origin rpy="1.5707963267949707 -0.5569332500522621 1.5567303253381135" xyz="-0.133937 0.00188408 -0.0297547"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
<joint name="rev6" type="revolute">
<parent link="l_J6_v002"/>
<child link="l_J7_v002"/>
<origin rpy="-1.5707963268025373 -1.5567303253381704 -0.5569332500438752" xyz="-0.0187648 -0.0301352 -0.12105"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
</joint>
<joint name="rev7" type="revolute">
<parent link="l_J7_v002"/>
<child link="l_J8_v002"/>
<origin rpy="-1.570796326795002 -0.008759049335348993 -0.014066001454933549" xyz="-0.000217313 -0.0154485 0.0355"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-0.9599310885968813" upper="0.9599310885968813" velocity="0.0"/>
</joint>
<joint name="gripper_right_jaw" type="prismatic">
<parent link="l_J8_v002"/>
<child link="l_right_jaw_v002"/>
<origin rpy="1.570796326794885 -0.014066001454926544 0.008759049336297665" xyz="-0.10571 -0.0781373 0.0132053"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0.0" upper="0.045" velocity="0.0"/>
<mimic joint="gripper_left_jaw" multiplier="-1.0" offset="0.0"/>
</joint>
<joint name="gripper_left_jaw" type="prismatic">
<parent link="l_J8_v002"/>
<child link="l_left_jaw_v002"/>
<origin rpy="1.5707963267948268 -0.014066001454925883 0.00875904933451695" xyz="-0.1071 0.07686 0.0132053"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0.0" upper="0.045" velocity="0.0"/>
</joint>
</robot>

View File

@ -1,5 +1,6 @@
<?xml version="1.0" encoding="utf-8"?> <?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm">
<xacro:include filename="openarm.urdf"/> <xacro:include filename="openarm.xacro.urdf"/>
<xacro:openarm/>
<xacro:include filename="openarm_sensors.urdf.xacro"/> <xacro:include filename="openarm_sensors.urdf.xacro"/>
</robot> </robot>

View File

@ -1,215 +0,0 @@
Panels:
- Class: rviz_common/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /RobotModel1
- /RobotModel1/Description Topic1
Splitter Ratio: 0.5
Tree Height: 1025
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
J2_v1_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
J3_v1_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
J4_v1_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
J5_v1_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
J6_v1_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
J7_v1_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
dummy:
Alpha: 1
Show Axes: false
Show Trail: false
grip_attach_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
left_jaw_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
right_jaw_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Mass Properties:
Inertia: false
Mass: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 0.8663532137870789
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.5453979969024658
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.7153980731964111
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1531
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001f4000004f9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000004f90000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d000004f9fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000006e000004f90000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000a970000005afc0100000002fb0000000800540069006d0065010000000000000a970000047a00fffffffb0000000800540069006d006501000000000000045000000000000000000000072e000004f900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 2711
X: 60
Y: 64

View File

@ -1,40 +0,0 @@
import os
import launch
import launch_ros
import xacro
from ament_index_python import get_package_share_directory
def get_package_file(package, file_path):
"""Get the location of a file installed in an ament package"""
package_path = get_package_share_directory(package)
absolute_file_path = os.path.join(package_path, file_path)
return absolute_file_path
def generate_launch_description():
xacro_file = get_package_file('openarm_grip_description', 'urdf/openarm_grip.xacro')
urdf = xacro.process_file(xacro_file).toprettyxml(indent=' ')
rviz_config_file = get_package_file('openarm_grip_description', 'config/display.rviz')
return launch.LaunchDescription([
launch_ros.actions.Node(
name='robot_state_publisher',
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{'robot_description': urdf}],
),
launch_ros.actions.Node(
name='joint_state_publisher_gui',
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
output='screen',
),
launch_ros.actions.Node(
name='rviz',
package='rviz2',
executable='rviz2',
output='screen',
arguments=['-d', rviz_config_file]
)
])

View File

@ -1,24 +0,0 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>openarm_grip_description</name>
<version>0.0.0</version>
<description>URDF models for OpenArm</description>
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
<license>BSD-3-Clause</license>
<depend>xacro</depend>
<depend>rviz2</depend>
<depend>robot_state_publisher</depend>
<depend>joint_state_publisher</depend>
<depend>joint_state_publisher_gui</depend>
<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>
<export>
<build_type>ament_python</build_type>
</export>
</package>

View File

@ -1,4 +0,0 @@
[develop]
script_dir=$base/lib/openarm_grip_description
[install]
install_scripts=$base/lib/openarm_grip_description

View File

@ -1,29 +0,0 @@
from setuptools import setup
import os
from glob import glob
package_name = "openarm_grip_description"
setup(
name=package_name,
version="0.0.0",
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
("share/" + package_name, ["package.xml"]),
(os.path.join("share", package_name, "launch"), glob("launch/*.launch.py")),
(os.path.join("share", package_name, "urdf"), glob("urdf/*")),
(os.path.join("share", package_name, "meshes"), glob("meshes/*")),
(os.path.join("share", package_name, "config"), glob("config/*")),
],
install_requires=["setuptools"],
zip_safe=True,
maintainer="Thomason",
maintainer_email="t95zhou@uwaterloo.ca",
description="URDF models for OpenArm",
license="BSD-3-Clause",
tests_require=["pytest"],
entry_points={
"console_scripts": [],
},
)

View File

@ -1,23 +0,0 @@
# Copyright 2015 Open Source Robotics Foundation, 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.
from ament_copyright.main import main
import pytest
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'

View File

@ -1,25 +0,0 @@
# Copyright 2017 Open Source Robotics Foundation, 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.
from ament_flake8.main import main_with_errors
import pytest
@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)

View File

@ -1,23 +0,0 @@
# Copyright 2015 Open Source Robotics Foundation, 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.
from ament_pep257.main import main
import pytest
@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'

View File

@ -1,8 +0,0 @@
<?xml version="1.0" ?>
<robot name="openarm_grip" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<material name="silver">
<color rgba="0.700 0.700 0.700 1.000"/>
</material>
</robot>

View File

@ -1,80 +0,0 @@
<?xml version="1.0" ?>
<robot name="openarm_grip" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:property name="body_color" value="Gazebo/Silver" />
<gazebo>
<plugin name="gz_ros2_control::GazeboSimROS2ControlPlugin" filename="gz_ros2_control-system"/>
</gazebo>
<gazebo reference="base_link">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
<gravity>true</gravity>
</gazebo>
<gazebo reference="J2_v1_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J3_v1_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J4_v1_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J5_v1_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J6_v1_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J7_v1_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="grip_attach_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="left_jaw_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="right_jaw_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
</robot>

View File

@ -1,103 +0,0 @@
<?xml version="1.0" ?>
<robot name="openarm_grip" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<transmission name="rev1_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev1_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev2_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev2_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev3_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev3_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev4_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev4_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev5_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev5_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev6_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev6_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev7_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev7">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev7_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="slider_left_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="slider_left">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="slider_left_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="slider_right_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="slider_right">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="slider_right_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>

View File

@ -1,443 +0,0 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from openarm_grip.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="openarm_grip">
<material name="silver">
<color rgba="0.700 0.700 0.700 1.000"/>
</material>
<transmission name="rev1_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev1_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev2_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev2_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev3_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev3_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev4_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev4_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev5_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev5_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev6_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev6_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="rev7_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rev7">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="rev7_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="slider_left_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="slider_left">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="slider_left_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="slider_right_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="slider_right">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="slider_right_actr">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin"/>
</gazebo>
<gazebo reference="base_link">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
<gravity>true</gravity>
</gazebo>
<gazebo reference="J2_v1_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J3_v1_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J4_v1_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J5_v1_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J6_v1_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="J7_v1_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="grip_attach_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="left_jaw_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="right_jaw_1">
<material>Gazebo/Silver</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>true</self_collide>
</gazebo>
<link name="world"/>
<joint name="world_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="1.659663993709495e-08 0.00015470291788827239 -0.03159176823669262"/>
<mass value="0.9159780860248254"/>
<inertia ixx="0.000802" ixy="-0.0" ixz="0.0" iyy="0.000799" iyz="-0.0" izz="0.001037"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J2_v1_1">
<inertial>
<origin rpy="0 0 0" xyz="0.002300730781673588 -0.00021691236314287158 0.02760602616888808"/>
<mass value="0.49220952328993495"/>
<inertia ixx="0.000316" ixy="0.0" ixz="-2.2e-05" iyy="0.000717" iyz="-3e-06" izz="0.00059"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.0 -0.0 0.00225"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.0 -0.0 0.00225"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J3_v1_1">
<inertial>
<origin rpy="0 0 0" xyz="-0.029725947365562236 0.014084733811091961 0.002458883521108013"/>
<mass value="0.6372830939810512"/>
<inertia ixx="0.000647" ixy="4e-06" ixz="2e-06" iyy="0.000437" iyz="-5.2e-05" izz="0.00075"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.02975 0.0 -0.0425"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.02975 0.0 -0.0425"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J4_v1_1">
<inertial>
<origin rpy="0 0 0" xyz="8.405076184644401e-05 0.1358717615053826 0.018429965102241944"/>
<mass value="1.1025467379280594"/>
<inertia ixx="0.011905" ixy="-1e-06" ixz="-4e-06" iyy="0.00114" iyz="-0.001657" izz="0.011791"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 -0.06041 -0.052607"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 -0.06041 -0.052607"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J5_v1_1">
<inertial>
<origin rpy="0 0 0" xyz="-0.028086778609557873 -0.06237848032279486 0.015103464347573828"/>
<mass value="0.7296865736952145"/>
<inertia ixx="0.002473" ixy="-7e-05" ixz="1.8e-05" iyy="0.000853" iyz="0.00038" izz="0.002847"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.029755 -0.298846 -0.0925"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.029755 -0.298846 -0.0925"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J6_v1_1">
<inertial>
<origin rpy="0 0 0" xyz="0.016428123043712856 -0.04271549352047854 0.009023923091251038"/>
<mass value="1.0339114396114095"/>
<inertia ixx="0.000881" ixy="0.000136" ixz="-1.1e-05" iyy="0.000614" iyz="0.000102" izz="0.001054"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 -0.167496 -0.118765"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 -0.167496 -0.118765"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J7_v1_1">
<inertial>
<origin rpy="0 0 0" xyz="-0.03510690863628159 0.0004066264284608781 0.001093657345024951"/>
<mass value="0.33288025570396623"/>
<inertia ixx="0.00014" ixy="-0.0" ixz="2e-06" iyy="0.000179" iyz="7e-06" izz="0.000207"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.0355 -0.048796 -0.1425"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.0355 -0.048796 -0.1425"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="grip_attach_1">
<inertial>
<origin rpy="0 0 0" xyz="-3.544262443517109e-05 -0.08091067772872827 0.004061313352520662"/>
<mass value="0.8188472642682024"/>
<inertia ixx="0.001113" ixy="1e-06" ixz="2e-06" iyy="0.00061" iyz="-2.2e-05" izz="0.001556"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 -0.051826 -0.15765"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 -0.051826 -0.15765"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_jaw_1">
<inertial>
<origin rpy="0 0 0" xyz="0.01737096632831872 -0.017398412728963003 0.004062150876211923"/>
<mass value="0.2869555939898112"/>
<inertia ixx="0.000209" ixy="1.6e-05" ixz="-4e-06" iyy="9.7e-05" iyz="3e-06" izz="0.000185"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0775 0.069829 -0.169736"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0775 0.069829 -0.169736"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_jaw_1">
<inertial>
<origin rpy="0 0 0" xyz="-0.0173972747583793 -0.018685385724924758 -0.0017497641003002828"/>
<mass value="0.285094009790996"/>
<inertia ixx="0.000211" ixy="-1.6e-05" ixz="4e-06" iyy="0.000115" iyz="3.9e-05" izz="0.000169"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.0775 0.069829 -0.169736"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.0775 0.069829 -0.169736"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="rev1" type="revolute">
<origin rpy="0 0 0" xyz="0.0 0.0 -0.00225"/>
<parent link="base_link"/>
<child link="J2_v1_1"/>
<axis xyz="0.0 0.0 1.0"/>
<limit acceleration="0.5" effort="100" lower="-2.356194" upper="2.356194" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev2" type="revolute">
<origin rpy="0 0 0" xyz="0.02975 -0.0 0.04475"/>
<parent link="J2_v1_1"/>
<child link="J3_v1_1"/>
<axis xyz="-1.0 -0.0 0.0"/>
<limit acceleration="0.5" effort="100" lower="-3.054326" upper="0.0" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev3" type="revolute">
<origin rpy="0 0 0" xyz="-0.02975 0.06041 0.010107"/>
<parent link="J3_v1_1"/>
<child link="J4_v1_1"/>
<axis xyz="-0.0 0.986291 0.165017"/>
<limit acceleration="0.5" effort="100" lower="-2.094395" upper="2.094395" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev4" type="revolute">
<origin rpy="0 0 0" xyz="0.029755 0.238436 0.039893"/>
<parent link="J4_v1_1"/>
<child link="J5_v1_1"/>
<axis xyz="1.0 0.0 0.0"/>
<limit acceleration="0.5" effort="100" lower="-3.141593" upper="0.0" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev5" type="revolute">
<origin rpy="0 0 0" xyz="-0.029755 -0.13135 0.026265"/>
<parent link="J5_v1_1"/>
<child link="J6_v1_1"/>
<axis xyz="0.0 -0.980588 0.196078"/>
<limit acceleration="0.5" effort="100" lower="-2.094395" upper="2.094395" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev6" type="revolute">
<origin rpy="0 0 0" xyz="0.0355 -0.1187 0.023735"/>
<parent link="J6_v1_1"/>
<child link="J7_v1_1"/>
<axis xyz="-1.0 0.0 -0.0"/>
<limit acceleration="0.5" effort="100" lower="-1.570796" upper="1.570796" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev7" type="revolute">
<origin rpy="0 0 0" xyz="-0.0355 0.00303 0.01515"/>
<parent link="J7_v1_1"/>
<child link="grip_attach_1"/>
<axis xyz="0.0 0.196078 0.980588"/>
<limit acceleration="0.5" effort="100" lower="-1.5" upper="1.5" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="slider_left" type="prismatic">
<origin rpy="0 0 0" xyz="-0.0775 -0.121655 0.012086"/>
<parent link="grip_attach_1"/>
<child link="left_jaw_1"/>
<axis xyz="-1.0 0.0 -0.0"/>
<limit acceleration="0.5" effort="100" lower="-0.0455" upper="0.0" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="slider_right" type="prismatic">
<origin rpy="0 0 0" xyz="0.0775 -0.121655 0.012086"/>
<parent link="grip_attach_1"/>
<child link="right_jaw_1"/>
<axis xyz="1.0 -0.0 0.0"/>
<limit acceleration="0.5" effort="100" lower="-0.0455" upper="0.0" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
<mimic joint="slider_left"/>
</joint>
</robot>

View File

@ -1,307 +0,0 @@
<?xml version="1.0" ?>
<robot name="openarm_grip" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="materials.xacro" />
<xacro:include filename="openarm_grip.trans" />
<xacro:include filename="openarm_grip.gazebo" />
<link name="world"/>
<joint name="world_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<link name="base_link">
<inertial>
<origin xyz="1.659663993709495e-08 0.00015470291788827239 -0.03159176823669262" rpy="0 0 0"/>
<mass value="0.9159780860248254"/>
<inertia ixx="0.000802" iyy="0.000799" izz="0.001037" ixy="-0.0" iyz="-0.0" ixz="0.0"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J2_v1_1">
<inertial>
<origin xyz="0.002300730781673588 -0.00021691236314287158 0.02760602616888808" rpy="0 0 0"/>
<mass value="0.49220952328993495"/>
<inertia ixx="0.000316" iyy="0.000717" izz="0.00059" ixy="0.0" iyz="-3e-06" ixz="-2.2e-05"/>
</inertial>
<visual>
<origin xyz="-0.0 -0.0 0.00225" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="-0.0 -0.0 0.00225" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J3_v1_1">
<inertial>
<origin xyz="-0.029725947365562236 0.014084733811091961 0.002458883521108013" rpy="0 0 0"/>
<mass value="0.6372830939810512"/>
<inertia ixx="0.000647" iyy="0.000437" izz="0.00075" ixy="4e-06" iyz="-5.2e-05" ixz="2e-06"/>
</inertial>
<visual>
<origin xyz="-0.02975 0.0 -0.0425" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="-0.02975 0.0 -0.0425" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J4_v1_1">
<inertial>
<origin xyz="8.405076184644401e-05 0.1358717615053826 0.018429965102241944" rpy="0 0 0"/>
<mass value="1.1025467379280594"/>
<inertia ixx="0.011905" iyy="0.00114" izz="0.011791" ixy="-1e-06" iyz="-0.001657" ixz="-4e-06"/>
</inertial>
<visual>
<origin xyz="0.0 -0.06041 -0.052607" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="0.0 -0.06041 -0.052607" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J5_v1_1">
<inertial>
<origin xyz="-0.028086778609557873 -0.06237848032279486 0.015103464347573828" rpy="0 0 0"/>
<mass value="0.7296865736952145"/>
<inertia ixx="0.002473" iyy="0.000853" izz="0.002847" ixy="-7e-05" iyz="0.00038" ixz="1.8e-05"/>
</inertial>
<visual>
<origin xyz="-0.029755 -0.298846 -0.0925" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="-0.029755 -0.298846 -0.0925" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J6_v1_1">
<inertial>
<origin xyz="0.016428123043712856 -0.04271549352047854 0.009023923091251038" rpy="0 0 0"/>
<mass value="1.0339114396114095"/>
<inertia ixx="0.000881" iyy="0.000614" izz="0.001054" ixy="0.000136" iyz="0.000102" ixz="-1.1e-05"/>
</inertial>
<visual>
<origin xyz="0.0 -0.167496 -0.118765" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="0.0 -0.167496 -0.118765" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="J7_v1_1">
<inertial>
<origin xyz="-0.03510690863628159 0.0004066264284608781 0.001093657345024951" rpy="0 0 0"/>
<mass value="0.33288025570396623"/>
<inertia ixx="0.00014" iyy="0.000179" izz="0.000207" ixy="-0.0" iyz="7e-06" ixz="2e-06"/>
</inertial>
<visual>
<origin xyz="-0.0355 -0.048796 -0.1425" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="-0.0355 -0.048796 -0.1425" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="grip_attach_1">
<inertial>
<origin xyz="-3.544262443517109e-05 -0.08091067772872827 0.004061313352520662" rpy="0 0 0"/>
<mass value="0.8188472642682024"/>
<inertia ixx="0.001113" iyy="0.00061" izz="0.001556" ixy="1e-06" iyz="-2.2e-05" ixz="2e-06"/>
</inertial>
<visual>
<origin xyz="0.0 -0.051826 -0.15765" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="0.0 -0.051826 -0.15765" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="left_jaw_1">
<inertial>
<origin xyz="0.01737096632831872 -0.017398412728963003 0.004062150876211923" rpy="0 0 0"/>
<mass value="0.2869555939898112"/>
<inertia ixx="0.000209" iyy="9.7e-05" izz="0.000185" ixy="1.6e-05" iyz="3e-06" ixz="-4e-06"/>
</inertial>
<visual>
<origin xyz="0.0775 0.069829 -0.169736" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="0.0775 0.069829 -0.169736" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="right_jaw_1">
<inertial>
<origin xyz="-0.0173972747583793 -0.018685385724924758 -0.0017497641003002828" rpy="0 0 0"/>
<mass value="0.285094009790996"/>
<inertia ixx="0.000211" iyy="0.000115" izz="0.000169" ixy="-1.6e-05" iyz="3.9e-05" ixz="4e-06"/>
</inertial>
<visual>
<origin xyz="-0.0775 0.069829 -0.169736" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin xyz="-0.0775 0.069829 -0.169736" rpy="0 0 0"/>
<geometry>
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="rev1" type="revolute">
<origin xyz="0.0 0.0 -0.00225" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="J2_v1_1"/>
<axis xyz="0.0 0.0 1.0"/>
<limit upper="2.356194" lower="-2.356194" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev2" type="revolute">
<origin xyz="0.02975 -0.0 0.04475" rpy="0 0 0"/>
<parent link="J2_v1_1"/>
<child link="J3_v1_1"/>
<axis xyz="-1.0 -0.0 0.0"/>
<limit upper="0.0" lower="-3.054326" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev3" type="revolute">
<origin xyz="-0.02975 0.06041 0.010107" rpy="0 0 0"/>
<parent link="J3_v1_1"/>
<child link="J4_v1_1"/>
<axis xyz="-0.0 0.986291 0.165017"/>
<limit upper="2.094395" lower="-2.094395" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev4" type="revolute">
<origin xyz="0.029755 0.238436 0.039893" rpy="0 0 0"/>
<parent link="J4_v1_1"/>
<child link="J5_v1_1"/>
<axis xyz="1.0 0.0 0.0"/>
<limit upper="0.0" lower="-3.141593" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev5" type="revolute">
<origin xyz="-0.029755 -0.13135 0.026265" rpy="0 0 0"/>
<parent link="J5_v1_1"/>
<child link="J6_v1_1"/>
<axis xyz="0.0 -0.980588 0.196078"/>
<limit upper="2.094395" lower="-2.094395" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev6" type="revolute">
<origin xyz="0.0355 -0.1187 0.023735" rpy="0 0 0"/>
<parent link="J6_v1_1"/>
<child link="J7_v1_1"/>
<axis xyz="-1.0 0.0 -0.0"/>
<limit upper="1.570796" lower="-1.570796" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="rev7" type="revolute">
<origin xyz="-0.0355 0.00303 0.01515" rpy="0 0 0"/>
<parent link="J7_v1_1"/>
<child link="grip_attach_1"/>
<axis xyz="0.0 0.196078 0.980588"/>
<limit upper="0.5" lower="-0.5" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="slider_left" type="prismatic">
<origin xyz="-0.0775 -0.121655 0.012086" rpy="0 0 0"/>
<parent link="grip_attach_1"/>
<child link="left_jaw_1"/>
<axis xyz="-1.0 0.0 -0.0"/>
<limit upper="0.0" lower="-0.0455" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<joint name="slider_right" type="prismatic">
<origin xyz="0.0775 -0.121655 0.012086" rpy="0 0 0"/>
<parent link="grip_attach_1"/>
<child link="right_jaw_1"/>
<axis xyz="1.0 -0.0 0.0"/>
<limit upper="0.0" lower="-0.0455" effort="100" velocity="1.0" acceleration="0.5"/>
<dynamics damping="1.0" friction="1.0"/>
<mimic joint="slider_left"/>
</joint>
</robot>

View File

@ -1,6 +1,6 @@
moveit_setup_assistant_config: moveit_setup_assistant_config:
urdf: urdf:
package: openarm_grip_description package: openarm_description
relative_path: urdf/openarm_grip.urdf relative_path: urdf/openarm_grip.urdf
srdf: srdf:
relative_path: config/openarm_grip.srdf relative_path: config/openarm_grip.srdf
@ -24,4 +24,4 @@ moveit_setup_assistant_config:
- velocity - velocity
state: state:
- position - position
- velocity - velocity

View File

@ -3,7 +3,7 @@
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" /> <xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
<!-- Import openarm_grip urdf file --> <!-- Import openarm_grip urdf file -->
<xacro:include filename="$(find openarm_grip_description)/urdf/openarm_grip.urdf" /> <xacro:include filename="$(find openarm_description)/urdf/openarm_grip.urdf" />
<!-- Import control_xacro --> <!-- Import control_xacro -->
<xacro:include filename="openarm_grip.ros2_control.xacro" /> <xacro:include filename="openarm_grip.ros2_control.xacro" />

View File

@ -36,7 +36,7 @@
<exec_depend>moveit_ros_visualization</exec_depend> <exec_depend>moveit_ros_visualization</exec_depend>
<exec_depend>moveit_ros_warehouse</exec_depend> <exec_depend>moveit_ros_warehouse</exec_depend>
<exec_depend>moveit_setup_assistant</exec_depend> <exec_depend>moveit_setup_assistant</exec_depend>
<exec_depend>openarm_grip_description</exec_depend> <exec_depend>openarm_description</exec_depend>
<exec_depend>robot_state_publisher</exec_depend> <exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend> <exec_depend>rviz2</exec_depend>
<exec_depend>rviz_common</exec_depend> <exec_depend>rviz_common</exec_depend>
@ -47,6 +47,6 @@
<export> <export>
<build_type>ament_cmake</build_type> <build_type>ament_cmake</build_type>
</export> </export>
</package> </package>

View File

@ -1,39 +0,0 @@
from pathlib import Path
import launch
from launch.substitutions import Command
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
import launch_ros
from launch_ros.parameter_descriptions import ParameterValue
def generate_launch_description():
pkg_share = Path(launch_ros.substitutions.FindPackageShare(package='openarm_two_arms').find('openarm_two_arms'))
default_model_path = pkg_share / 'urdf/openarm_two_arms_wrapper.urdf.xacro'
use_sim_time = LaunchConfiguration('use_sim_time')
use_sim_time_launch_arg = DeclareLaunchArgument('use_sim_time', default_value='true')
robot_state_publisher_node = launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[
{
# ParameterValue is required to avoid being interpreted as YAML.
'robot_description': ParameterValue(Command(['xacro ', LaunchConfiguration('model')]), value_type=str),
'use_sim_time': use_sim_time,
},
],
)
return launch.LaunchDescription([
launch.actions.DeclareLaunchArgument(
name='model',
default_value=str(default_model_path),
description="Absolute path to the robot's URDF file",
),
use_sim_time_launch_arg,
robot_state_publisher_node,
])

View File

@ -1,84 +0,0 @@
from pathlib import Path
import launch
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
import launch_ros
from launch_ros.substitutions import FindPackageShare
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
pkg_share = Path(launch_ros.substitutions.FindPackageShare(package='openarm_two_arms').find('openarm_two_arms'))
default_model_path = pkg_share / 'urdf/openarm_two_arms_wrapper.urdf.xacro'
default_rviz_config_path = pkg_share / 'rviz/robot_description.rviz'
use_sim_time = LaunchConfiguration('use_sim_time')
robot_state_publisher_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare('openarm_two_arms'),
'launch',
'description.launch.py',
]),
]),
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
joint_state_publisher_node = launch_ros.actions.Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
condition=launch.conditions.UnlessCondition(LaunchConfiguration('gui')),
parameters=[{
'use_sim_time': use_sim_time,
}],
)
joint_state_publisher_gui_node = launch_ros.actions.Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui',
condition=launch.conditions.IfCondition(LaunchConfiguration('gui')),
parameters=[{
'use_sim_time': use_sim_time,
}],
)
rviz_node = launch_ros.actions.Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', LaunchConfiguration('rvizconfig')],
parameters=[{
'use_sim_time': use_sim_time,
}],
)
return launch.LaunchDescription([
launch.actions.DeclareLaunchArgument(
name='use_sim_time',
default_value='false',
description='Flag to enable usage of simulation time',
),
launch.actions.DeclareLaunchArgument(
name='gui',
default_value='True',
description='Flag to enable joint_state_publisher_gui',
),
launch.actions.DeclareLaunchArgument(
name='model',
default_value=str(default_model_path),
description='Absolute path to robot urdf file',
),
launch.actions.DeclareLaunchArgument(
name='rvizconfig',
default_value=str(default_rviz_config_path),
description='Absolute path to rviz config file',
),
joint_state_publisher_node,
joint_state_publisher_gui_node,
robot_state_publisher_node,
rviz_node,
])

View File

@ -1,128 +0,0 @@
import os
import re
import subprocess
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
resources_package = 'openarm_two_arms'
# Make path to resources dir without last package_name fragment.
path_to_share_dir_clipped = ''.join(get_package_share_directory(resources_package).rsplit('/' + resources_package, 1))
# Gazebo hint for resources.
os.environ['GZ_SIM_RESOURCE_PATH'] = path_to_share_dir_clipped
# Ensure `SDF_PATH` is populated since `sdformat_urdf` uses this rather
# than `GZ_SIM_RESOURCE_PATH` to locate resources.
if "GZ_SIM_RESOURCE_PATH" in os.environ:
gz_sim_resource_path = os.environ["GZ_SIM_RESOURCE_PATH"]
if "SDF_PATH" in os.environ:
sdf_path = os.environ["SDF_PATH"]
os.environ["SDF_PATH"] = sdf_path + ":" + gz_sim_resource_path
else:
os.environ["SDF_PATH"] = gz_sim_resource_path
use_custom_world = LaunchConfiguration('use_custom_world')
use_custom_world_launch_arg = DeclareLaunchArgument('use_custom_world', default_value='true')
gazebo_world = LaunchConfiguration('gazebo_world')
gazebo_world_launch_arg = DeclareLaunchArgument('gazebo_world', default_value='empty.sdf')
# prepare custom world
world = os.getenv('GZ_SIM_WORLD', 'empty')
fly_world_path = resources_package + '/worlds/' + world + '.sdf'
gz_version = subprocess.getoutput("gz sim --versions")
gz_version_major = re.search(r'^\d{1}', gz_version).group()
launch_arguments=dict(gz_args = '-r ' + str(fly_world_path) + ' --verbose ', gz_version = gz_version_major).items()
# Gazebo Sim.
# by default the custom world is used, otherwise the gazebo world is used, which can be changed with the argument
pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim')
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py'),
),
launch_arguments=launch_arguments if use_custom_world else dict(gz_args='-r ' + gazebo_world + ' --verbose').items(),
)
# Spawn
spawn = Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-name', 'openarm_two_arms',
'-x', '1.2',
'-z', '2.3',
'-Y', '3.4',
'-topic', '/robot_description',
],
output='screen',
)
use_sim_time = LaunchConfiguration('use_sim_time')
use_sim_time_launch_arg = DeclareLaunchArgument('use_sim_time', default_value='true')
use_rviz = LaunchConfiguration('use_rviz')
use_rviz_arg = DeclareLaunchArgument("use_rviz", default_value='true')
robot_state_publisher = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare(resources_package),
'launch',
'description.launch.py',
]),
]),
condition=UnlessCondition(use_rviz), # rviz launch includes rsp.
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
rviz = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare(resources_package),
'launch',
'display.launch.py',
]),
]),
condition=IfCondition(use_rviz),
launch_arguments=dict(use_sim_time=use_sim_time).items(),
)
gz_bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=['/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock'],
output='screen',
parameters=[{
'use_sim_time': use_sim_time,
}],
)
return LaunchDescription([
use_sim_time_launch_arg,
use_rviz_arg,
use_custom_world_launch_arg,
gazebo_world_launch_arg,
robot_state_publisher,
rviz,
gazebo,
spawn,
gz_bridge,
])

View File

@ -1,5 +0,0 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_two_arms">
<xacro:include filename="openarm_two_arms.urdf.xacro"/>
<xacro:include filename="openarm_two_arms_sensors.urdf.xacro"/>
</robot>

View File

@ -1,27 +0,0 @@
controller_manager:
ros__parameters:
update_rate: 250
gripper_action_controller_position:
type: position_controllers/GripperActionController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
gripper_action_controller_position:
ros__parameters:
action_monitor_rate: 20.0
allow_stalling: false
goal_tolerance: 0.01
joint: null
max_effort: 0.0
stall_timeout: 1.0
stall_velocity_threshold: 0.001
joint_state_broadcaster:
ros__parameters:
map_interface_to_joint_state.effort: effort
map_interface_to_joint_state.position: position
map_interface_to_joint_state.velocity: velocity
use_local_topics: false
use_urdf_to_filter: true
joint_group_position_controller:
ros__parameters: {}

View File

@ -1,86 +0,0 @@
<?xml version="1.0" ?>
<robotMeta>
<robotName>openarm</robotName>
<urdfFileName>openarm.urdf</urdfFileName>
<packageName>openarm_description_2</packageName>
<meshesDir>meshes </meshesDir>
<robotType>nonspecific</robotType>
<generateCodeForRosVersion>jazzy</generateCodeForRosVersion>
<rootLinkName>l_J1_v002</rootLinkName>
<xacroWrapperFileName>openarm_wrapper.urdf.xacro</xacroWrapperFileName>
<controllersConfigFileName>openarm_controllers.yaml</controllersConfigFileName>
<joints>
<joint>
<name>rev1</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.09289716518533317</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.0012062241015717492</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>-0.061900576071863</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>rev2</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.09289716518533321</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>-0.02854377589842827</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>-0.017150576071863013</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>rev3</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.031649514284448864</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.0012062241015718708</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>-0.01661414422754956</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>rev4</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>-0.20983062047238518</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.033077014697707</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>-0.016614144227858844</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>rev5</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>-0.08488103444256599</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.0022268460560923354</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>0.030965376793060356</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>rev6</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.02795991840243387</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>-0.03426282248752859</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>0.07396277148947943</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>rev7</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.033758514926782335</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.001187752615916666</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>0.05952028198168136</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>gripper_right_jaw</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.0</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.0</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>0.0</jointRelTotalCenterOfMass_z>
</joint>
<joint>
<name>gripper_left_jaw</name>
<jointSpecific>unset</jointSpecific>
<jointRotationDirection>unset</jointRotationDirection>
<jointRelTotalCenterOfMass_x>0.0</jointRelTotalCenterOfMass_x>
<jointRelTotalCenterOfMass_y>0.0</jointRelTotalCenterOfMass_y>
<jointRelTotalCenterOfMass_z>0.0</jointRelTotalCenterOfMass_z>
</joint>
</joints>
</robotMeta>