robot description publisher service is added
This commit is contained in:
parent
d068108b44
commit
f72dc3e583
13
Makefile
13
Makefile
|
@ -4,6 +4,9 @@ hesai:
|
|||
bridge:
|
||||
@cd deploy && docker build --no-cache --tag go2py_bridge:latest -f docker/Dockerfile.bridge .
|
||||
|
||||
robot_description:
|
||||
@cd deploy && docker build --no-cache --tag go2py_description:latest -f docker/Dockerfile.robot_description .
|
||||
|
||||
hesai_install:
|
||||
@cp deploy/services/go2py-hesai.service /etc/systemd/system/
|
||||
@systemctl enable go2py-hesai.service
|
||||
|
@ -14,6 +17,11 @@ bridge_install:
|
|||
@systemctl enable go2py-bridge.service
|
||||
@systemctl start go2py-bridge.service
|
||||
|
||||
robot_description_install:
|
||||
@cp deploy/services/go2py-robot-description.service /etc/systemd/system/
|
||||
@systemctl enable go2py-robot-description.service
|
||||
@systemctl start go2py-robot-description.service
|
||||
|
||||
hesai_uninstall:
|
||||
@systemctl disable go2py-hesai.service
|
||||
@systemctl stop go2py-hesai.service
|
||||
|
@ -23,3 +31,8 @@ bridge_uninstall:
|
|||
@systemctl disable go2py-bridge.service
|
||||
@systemctl stop go2py-bridge.service
|
||||
@rm /etc/systemd/system/go2py-bridge.service
|
||||
|
||||
robot_description_uninstall:
|
||||
@systemctl disable go2py-robot-description.service
|
||||
@systemctl stop go2py-robot-description.service
|
||||
@rm /etc/systemd/system/go2py-robot-description.service
|
|
@ -0,0 +1,31 @@
|
|||
# FROM isaac_ros_dev-aarch64
|
||||
FROM ros:humble
|
||||
ENV DEBIAN_FRONTEND=noninteractive
|
||||
SHELL ["/bin/bash", "-c"]
|
||||
# uodate and install dependencies
|
||||
RUN apt-get update && apt-get install -y \
|
||||
ros-humble-rmw-cyclonedds-cpp ros-humble-rosidl-generator-dds-idl \
|
||||
libyaml-cpp-dev \
|
||||
ros-humble-xacro \
|
||||
libboost-all-dev\
|
||||
build-essential \
|
||||
cmake \
|
||||
git \
|
||||
&& rm -rf /var/lib/apt/lists/*
|
||||
|
||||
# Cheange the ROS2 RMW to CycloneDDS as instructed by Unitree
|
||||
RUN cd / && git clone https://github.com/unitreerobotics/unitree_ros2 && cd /unitree_ros2/cyclonedds_ws/src && \
|
||||
git clone https://github.com/ros2/rmw_cyclonedds -b humble && git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x &&\
|
||||
cd .. && colcon build --packages-select cyclonedds && source /opt/ros/humble/setup.bash && colcon build
|
||||
|
||||
# ros2 nodes
|
||||
COPY ros2_nodes/go2_description /ros2_ws/src/go2_description
|
||||
RUN cd /ros2_ws && source /opt/ros/humble/setup.bash && source /unitree_ros2/cyclonedds_ws/install/setup.bash && colcon build --symlink-install
|
||||
|
||||
# Copy the script to start the nodes
|
||||
COPY docker/scripts /root/scripts
|
||||
COPY launch_files /root/launch
|
||||
|
||||
# set the entrypoint to bash
|
||||
#ENTRYPOINT ["/bin/bash"]
|
||||
ENTRYPOINT ["/bin/bash", "/root/scripts/robot_description.sh"]
|
|
@ -0,0 +1,4 @@
|
|||
source /opt/ros/humble/setup.bash
|
||||
source /unitree_ros2/cyclonedds_ws/install/setup.bash
|
||||
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
|
||||
source /ros2_ws/install/setup.bash && ros2 launch /root/launch/robot_description.launch.py
|
|
@ -1,38 +1,22 @@
|
|||
from launch import LaunchDescription
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import ThisLaunchFileDir
|
||||
from launch_ros.actions import Node
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
user_debug_parameter_name = "user_debug"
|
||||
user_debug = LaunchConfiguration(user_debug_parameter_name)
|
||||
# prefix = LaunchConfiguration("prefix", default="go2/")
|
||||
|
||||
go2_xacro_file = os.path.join(
|
||||
get_package_share_directory("go2_description"),
|
||||
"xacro",
|
||||
"robot_virtual_arm.xacro",
|
||||
get_package_share_directory("go2_description"), "xacro", "robot.xacro"
|
||||
)
|
||||
robot_description = Command(
|
||||
[FindExecutable(name="xacro"), " ", go2_xacro_file, " DEBUG:=", user_debug]
|
||||
[FindExecutable(name="xacro"), " ", go2_xacro_file, " DEBUG:=", 'false']
|
||||
)
|
||||
|
||||
rviz_file = os.path.join(
|
||||
get_package_share_directory("go2_description"), "launch", "visualize_go2.rviz"
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
DeclareLaunchArgument(
|
||||
user_debug_parameter_name,
|
||||
default_value="false",
|
||||
description="debug or not",
|
||||
),
|
||||
Node(
|
||||
return LaunchDescription([
|
||||
Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
name="robot_state_publisher",
|
||||
|
@ -43,13 +27,7 @@ def generate_launch_description():
|
|||
("/robot_description", "/go2/robot_description"),
|
||||
],
|
||||
),
|
||||
Node(
|
||||
package="rviz2",
|
||||
executable="rviz2",
|
||||
name="rviz2",
|
||||
arguments=["--display-config", rviz_file],
|
||||
),
|
||||
Node(
|
||||
Node(
|
||||
package="tf2_ros",
|
||||
executable="static_transform_publisher",
|
||||
arguments=[
|
||||
|
@ -65,5 +43,4 @@ def generate_launch_description():
|
|||
],
|
||||
name="static_tf_pub_trunk_to_lidar",
|
||||
),
|
||||
]
|
||||
)
|
||||
])
|
|
@ -41,27 +41,27 @@ def generate_launch_description():
|
|||
("/robot_description", "/go2/robot_description"),
|
||||
],
|
||||
),
|
||||
Node(
|
||||
package="rviz2",
|
||||
executable="rviz2",
|
||||
name="rviz2",
|
||||
arguments=["--display-config", rviz_file],
|
||||
),
|
||||
Node(
|
||||
package="tf2_ros",
|
||||
executable="static_transform_publisher",
|
||||
arguments=[
|
||||
"0.15",
|
||||
"0",
|
||||
"0.15",
|
||||
"0",
|
||||
"0",
|
||||
"0.707107",
|
||||
"0.707107",
|
||||
"/trunk",
|
||||
"/go2/hesai_lidar",
|
||||
],
|
||||
name="static_tf_pub_trunk_to_lidar",
|
||||
),
|
||||
# Node(
|
||||
# package="rviz2",
|
||||
# executable="rviz2",
|
||||
# name="rviz2",
|
||||
# arguments=["--display-config", rviz_file],
|
||||
# ),
|
||||
# Node(
|
||||
# package="tf2_ros",
|
||||
# executable="static_transform_publisher",
|
||||
# arguments=[
|
||||
# "0.15",
|
||||
# "0",
|
||||
# "0.15",
|
||||
# "0",
|
||||
# "0",
|
||||
# "0.707107",
|
||||
# "0.707107",
|
||||
# "/trunk",
|
||||
# "/go2/hesai_lidar",
|
||||
# ],
|
||||
# name="static_tf_pub_trunk_to_lidar",
|
||||
# ),
|
||||
]
|
||||
)
|
||||
|
|
|
@ -1,469 +0,0 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="go2">
|
||||
<material name="black">
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="blue">
|
||||
<color rgba="0.0 0.0 0.8 1.0"/>
|
||||
</material>
|
||||
<material name="green">
|
||||
<color rgba="0.0 0.8 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="grey">
|
||||
<color rgba="0.2 0.2 0.2 0.0"/>
|
||||
</material>
|
||||
<material name="silver">
|
||||
<color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/>
|
||||
</material>
|
||||
<material name="orange">
|
||||
<color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
|
||||
</material>
|
||||
<material name="brown">
|
||||
<color rgba="0.8705882352941177 0.8117647058823529 0.7647058823529411 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="white">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<link name="base">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.3762 0.0935 0.114"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.021112 0.0 -0.005366"/>
|
||||
<mass value="6.921"/>
|
||||
<inertia ixx="0.02448" ixy="0.00012166" ixz="0.0014849" iyy="0.098077" iyz="-3.12e-05" izz="0.107"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<!-- <material name="red"/> -->
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1934 -0.0465 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="FR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.0955 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.0054 -0.00194 -0.000105"/>
|
||||
<mass value="0.678"/>
|
||||
<inertia ixx="0.00048" ixy="3.01e-06" ixz="1.11e-06" iyy="0.000884" iyz="1.42e-06" izz="0.000596"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.0955 0"/>
|
||||
<parent link="FR_hip"/>
|
||||
<child link="FR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="FR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/>
|
||||
<mass value="1.152"/>
|
||||
<inertia ixx="0.00584" ixy="-8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FR_thigh"/>
|
||||
<child link="FR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="35.55" lower="-2.7227" upper="-0.83776" velocity="20.06"/>
|
||||
</joint>
|
||||
<link name="FR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
|
||||
<mass value="0.154"/>
|
||||
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FR_calf"/>
|
||||
<child link="FR_foot"/>
|
||||
</joint>
|
||||
<link name="FR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="FL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.1934 0.0465 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="FL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="FL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0.0955 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.0054 0.00194 -0.000105"/>
|
||||
<mass value="0.678"/>
|
||||
<inertia ixx="0.00048" ixy="-3.01e-06" ixz="1.11e-06" iyy="0.000884" iyz="-1.42e-06" izz="0.000596"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.0955 0"/>
|
||||
<parent link="FL_hip"/>
|
||||
<child link="FL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="FL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/>
|
||||
<mass value="1.152"/>
|
||||
<inertia ixx="0.00584" ixy="8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FL_thigh"/>
|
||||
<child link="FL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="35.55" lower="-2.7227" upper="-0.83776" velocity="20.06"/>
|
||||
</joint>
|
||||
<link name="FL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
|
||||
<mass value="0.154"/>
|
||||
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="FL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="FL_calf"/>
|
||||
<child link="FL_foot"/>
|
||||
</joint>
|
||||
<link name="FL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="RR_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.1934 -0.0465 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RR_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="RR_hip">
|
||||
<visual>
|
||||
<origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.0955 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0054 -0.00194 -0.000105"/>
|
||||
<mass value="0.678"/>
|
||||
<inertia ixx="0.00048" ixy="-3.01e-06" ixz="-1.11e-06" iyy="0.000884" iyz="1.42e-06" izz="0.000596"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.0955 0"/>
|
||||
<parent link="RR_hip"/>
|
||||
<child link="RR_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="RR_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/>
|
||||
<mass value="1.152"/>
|
||||
<inertia ixx="0.00584" ixy="-8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RR_thigh"/>
|
||||
<child link="RR_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="35.55" lower="-2.7227" upper="-0.83776" velocity="20.06"/>
|
||||
</joint>
|
||||
<link name="RR_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
|
||||
<mass value="0.154"/>
|
||||
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RR_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RR_calf"/>
|
||||
<child link="RR_foot"/>
|
||||
</joint>
|
||||
<link name="RR_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.01"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="RL_hip_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.1934 0.0465 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="RL_hip"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="RL_hip">
|
||||
<visual>
|
||||
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0.0955 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.04" radius="0.046"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0054 0.00194 -0.000105"/>
|
||||
<mass value="0.678"/>
|
||||
<inertia ixx="0.00048" ixy="3.01e-06" ixz="-1.11e-06" iyy="0.000884" iyz="-1.42e-06" izz="0.000596"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0.0955 0"/>
|
||||
<parent link="RL_hip"/>
|
||||
<child link="RL_thigh"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
|
||||
</joint>
|
||||
<link name="RL_thigh">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.0245 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/>
|
||||
<mass value="1.152"/>
|
||||
<inertia ixx="0.00584" ixy="8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RL_thigh"/>
|
||||
<child link="RL_calf"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="0.01" friction="0.2"/>
|
||||
<limit effort="35.55" lower="-2.7227" upper="-0.83776" velocity="20.06"/>
|
||||
</joint>
|
||||
<link name="RL_calf">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
|
||||
<geometry>
|
||||
<box size="0.213 0.016 0.016"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
|
||||
<mass value="0.154"/>
|
||||
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="RL_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
|
||||
<parent link="RL_calf"/>
|
||||
<child link="RL_foot"/>
|
||||
</joint>
|
||||
<link name="RL_foot">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.02"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.06"/>
|
||||
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
|
||||
</inertial>
|
||||
</link>
|
||||
</robot>
|
|
@ -91,33 +91,7 @@
|
|||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<!--
|
||||
<joint name="load_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="load_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="load_link">
|
||||
<inertial>
|
||||
<mass value="5"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.2"/>
|
||||
<geometry>
|
||||
<box size="0.5 0.3 0.2"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
-->
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True" />
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True" />
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False" />
|
||||
|
|
|
@ -1,147 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="go2" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:arg name="DEBUG" default="false"/>
|
||||
|
||||
<xacro:include filename="$(find go2_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find go2_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find go2_description)/xacro/leg.xacro"/>
|
||||
<!-- <xacro:include filename="$(find go2_description)/xacro/stairs.xacro"/> -->
|
||||
<xacro:include filename="$(find go2_description)/xacro/gazebo.xacro"/>
|
||||
<!-- <xacro:include filename="$(find go2_gazebo)/launch/stairs.urdf.xacro"/> -->
|
||||
|
||||
<!-- <xacro:stairs stairs="15" xpos="0" ypos="0" zpos="0" /> -->
|
||||
|
||||
<!-- Rotor related joint and link is only for demonstrate location. -->
|
||||
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
|
||||
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<xacro:if value="$(arg DEBUG)">
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base_link"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="floating_base" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="trunk"/>
|
||||
</joint>
|
||||
|
||||
<link name="trunk">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://go2_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<!-- <material name="orange"/> -->
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
|
||||
<mass value="${trunk_mass}"/>
|
||||
<inertia
|
||||
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
|
||||
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
|
||||
izz="${trunk_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="imu_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="imu_link">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<!-- <material name="red"/> -->
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="virtual_arm">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="1.0 0.0 0.0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://go2_description/meshes/virtual_arm.dae"/>
|
||||
</geometry>
|
||||
<material name="red">
|
||||
<color rgba="1. 0. 0. 0.5"/>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name="virtual_arm_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="virtual_arm"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<dynamics damping="0" friction="0"/>
|
||||
<limit effort="100.0" lower="-3.1416" upper="3.1416" velocity="20.0"/>
|
||||
</joint>
|
||||
|
||||
<!--
|
||||
<joint name="load_joint" type="fixed">
|
||||
<parent link="trunk"/>
|
||||
<child link="load_link"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="load_link">
|
||||
<inertial>
|
||||
<mass value="5"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.2"/>
|
||||
<geometry>
|
||||
<box size="0.5 0.3 0.2"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".001 .001 .001"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
-->
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True" />
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True" />
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False" />
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False" />
|
||||
</robot>
|
|
@ -1,64 +0,0 @@
|
|||
cmake_minimum_required(VERSION 3.5)
|
||||
project(unitree_api)
|
||||
|
||||
# Default to C99
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
endif()
|
||||
|
||||
# Default to C++14
|
||||
if(NOT CMAKE_CXX_STANDARD)
|
||||
set(CMAKE_CXX_STANDARD 14)
|
||||
endif()
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
# uncomment the following section in order to fill in
|
||||
# further dependencies manually.
|
||||
# find_package(<dependency> REQUIRED)
|
||||
|
||||
find_package(geometry_msgs REQUIRED)
|
||||
find_package(rosidl_default_generators REQUIRED)
|
||||
find_package(rosidl_generator_dds_idl REQUIRED)
|
||||
|
||||
rosidl_generate_interfaces(${PROJECT_NAME}
|
||||
"msg/Request.msg"
|
||||
"msg/RequestHeader.msg"
|
||||
"msg/RequestIdentity.msg"
|
||||
"msg/RequestLease.msg"
|
||||
"msg/RequestPolicy.msg"
|
||||
"msg/Response.msg"
|
||||
"msg/ResponseHeader.msg"
|
||||
"msg/ResponseStatus.msg"
|
||||
|
||||
DEPENDENCIES geometry_msgs
|
||||
)
|
||||
|
||||
rosidl_generate_dds_interfaces(
|
||||
${rosidl_generate_interfaces_TARGET}__dds_connext_idl
|
||||
IDL_TUPLES ${rosidl_generate_interfaces_IDL_TUPLES}
|
||||
OUTPUT_SUBFOLDERS "dds_connext"
|
||||
)
|
||||
add_dependencies(
|
||||
${PROJECT_NAME}
|
||||
${PROJECT_NAME}__dds_connext_idl
|
||||
)
|
||||
|
||||
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# uncomment the line when a copyright and license is not present in all source files
|
||||
#set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# uncomment the line when this package is not in a git repo
|
||||
#set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
ament_package()
|
|
@ -1,3 +0,0 @@
|
|||
RequestHeader header
|
||||
string parameter
|
||||
uint8[] binary
|
|
@ -1,3 +0,0 @@
|
|||
RequestIdentity identity
|
||||
RequestLease lease
|
||||
RequestPolicy policy
|
|
@ -1,2 +0,0 @@
|
|||
int64 id
|
||||
int64 api_id
|
|
@ -1 +0,0 @@
|
|||
int64 id
|
|
@ -1,2 +0,0 @@
|
|||
int32 priority
|
||||
bool noreply
|
|
@ -1,3 +0,0 @@
|
|||
ResponseHeader header
|
||||
string data
|
||||
int8[] binary
|
|
@ -1,2 +0,0 @@
|
|||
RequestIdentity identity
|
||||
ResponseStatus status
|
|
@ -1 +0,0 @@
|
|||
int32 code
|
|
@ -1,23 +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>unitree_api</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="czk@todo.todo">czk</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<build_depend>rosidl_default_generators</build_depend>
|
||||
<exec_depend>rosidl_default_runtime</exec_depend>
|
||||
<member_of_group>rosidl_interface_packages</member_of_group>
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>geometry_msgs</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
|
@ -0,0 +1,13 @@
|
|||
[Unit]
|
||||
Description=ROS2 device driver container
|
||||
Requires=multi-user.target
|
||||
After=multi-user.target
|
||||
|
||||
[Service]
|
||||
Restart=always
|
||||
ExecStartPre=/usr/bin/docker rm -f go2py_robot_description || true
|
||||
ExecStart=/bin/bash -c '/usr/bin/docker run --rm --name go2py_robot_description --privileged --network host -v /home/unitree/locomotion:/home/locomotion -v /dev/*:/dev/* -v /etc/localtime:/etc/localtime:ro --runtime nvidia go2py_description:latest'
|
||||
ExecStop=/usr/bin/docker stop -t 2 go2py_robot_description
|
||||
|
||||
[Install]
|
||||
WantedBy=default.target
|
Loading…
Reference in New Issue