Upload aliengoZ1_description
This commit is contained in:
parent
6e033297dc
commit
309d2e0fab
|
@ -0,0 +1,207 @@
|
|||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(aliengoZ1_description)
|
||||
|
||||
## Compile as C++11, supported in ROS Kinetic and newer
|
||||
# add_compile_options(-std=c++11)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
rospy
|
||||
urdf
|
||||
xacro
|
||||
)
|
||||
|
||||
## System dependencies are found with CMake's conventions
|
||||
# find_package(Boost REQUIRED COMPONENTS system)
|
||||
|
||||
|
||||
## Uncomment this if the package has a setup.py. This macro ensures
|
||||
## modules and global scripts declared therein get installed
|
||||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
||||
# catkin_python_setup()
|
||||
|
||||
################################################
|
||||
## Declare ROS messages, services and actions ##
|
||||
################################################
|
||||
|
||||
## To declare and build messages, services or actions from within this
|
||||
## package, follow these steps:
|
||||
## * Let MSG_DEP_SET be the set of packages whose message types you use in
|
||||
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
|
||||
## * In the file package.xml:
|
||||
## * add a build_depend tag for "message_generation"
|
||||
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
|
||||
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
|
||||
## but can be declared for certainty nonetheless:
|
||||
## * add a exec_depend tag for "message_runtime"
|
||||
## * In this file (CMakeLists.txt):
|
||||
## * add "message_generation" and every package in MSG_DEP_SET to
|
||||
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||
## * add "message_runtime" and every package in MSG_DEP_SET to
|
||||
## catkin_package(CATKIN_DEPENDS ...)
|
||||
## * uncomment the add_*_files sections below as needed
|
||||
## and list every .msg/.srv/.action file to be processed
|
||||
## * uncomment the generate_messages entry below
|
||||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
# add_message_files(
|
||||
# FILES
|
||||
# Message1.msg
|
||||
# Message2.msg
|
||||
# )
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
# add_service_files(
|
||||
# FILES
|
||||
# Service1.srv
|
||||
# Service2.srv
|
||||
# )
|
||||
|
||||
## Generate actions in the 'action' folder
|
||||
# add_action_files(
|
||||
# FILES
|
||||
# Action1.action
|
||||
# Action2.action
|
||||
# )
|
||||
|
||||
## Generate added messages and services with any dependencies listed here
|
||||
# generate_messages(
|
||||
# DEPENDENCIES
|
||||
# std_msgs # Or other packages containing msgs
|
||||
# )
|
||||
|
||||
################################################
|
||||
## Declare ROS dynamic reconfigure parameters ##
|
||||
################################################
|
||||
|
||||
## To declare and build dynamic reconfigure parameters within this
|
||||
## package, follow these steps:
|
||||
## * In the file package.xml:
|
||||
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
|
||||
## * In this file (CMakeLists.txt):
|
||||
## * add "dynamic_reconfigure" to
|
||||
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||
## * uncomment the "generate_dynamic_reconfigure_options" section below
|
||||
## and list every .cfg file to be processed
|
||||
|
||||
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
||||
# generate_dynamic_reconfigure_options(
|
||||
# cfg/DynReconf1.cfg
|
||||
# cfg/DynReconf2.cfg
|
||||
# )
|
||||
|
||||
###################################
|
||||
## catkin specific configuration ##
|
||||
###################################
|
||||
## The catkin_package macro generates cmake config files for your package
|
||||
## Declare things to be passed to dependent projects
|
||||
## INCLUDE_DIRS: uncomment this if your package contains header files
|
||||
## LIBRARIES: libraries you create in this project that dependent projects also need
|
||||
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||
catkin_package(
|
||||
# INCLUDE_DIRS include
|
||||
# LIBRARIES aliengoAndarm
|
||||
# CATKIN_DEPENDS roscpp rospy urdf xacro
|
||||
# DEPENDS system_lib
|
||||
)
|
||||
|
||||
###########
|
||||
## Build ##
|
||||
###########
|
||||
|
||||
## Specify additional locations of header files
|
||||
## Your package locations should be listed before other locations
|
||||
include_directories(
|
||||
# include
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
## Declare a C++ library
|
||||
# add_library(${PROJECT_NAME}
|
||||
# src/${PROJECT_NAME}/aliengoAndarm.cpp
|
||||
# )
|
||||
|
||||
## Add cmake target dependencies of the library
|
||||
## as an example, code may need to be generated before libraries
|
||||
## either from message generation or dynamic reconfigure
|
||||
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Declare a C++ executable
|
||||
## With catkin_make all packages are built within a single CMake context
|
||||
## The recommended prefix ensures that target names across packages don't collide
|
||||
# add_executable(${PROJECT_NAME}_node src/aliengoAndarm_node.cpp)
|
||||
|
||||
## Rename C++ executable without prefix
|
||||
## The above recommended prefix causes long target names, the following renames the
|
||||
## target back to the shorter version for ease of user use
|
||||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
|
||||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
|
||||
|
||||
## Add cmake target dependencies of the executable
|
||||
## same as for the library above
|
||||
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
# target_link_libraries(${PROJECT_NAME}_node
|
||||
# ${catkin_LIBRARIES}
|
||||
# )
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
||||
# all install targets should use catkin DESTINATION variables
|
||||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
||||
|
||||
## Mark executable scripts (Python etc.) for installation
|
||||
## in contrast to setup.py, you can choose the destination
|
||||
# catkin_install_python(PROGRAMS
|
||||
# scripts/my_python_script
|
||||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark executables for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
|
||||
# install(TARGETS ${PROJECT_NAME}_node
|
||||
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark libraries for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
|
||||
# install(TARGETS ${PROJECT_NAME}
|
||||
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark cpp header files for installation
|
||||
# install(DIRECTORY include/${PROJECT_NAME}/
|
||||
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
# FILES_MATCHING PATTERN "*.h"
|
||||
# PATTERN ".svn" EXCLUDE
|
||||
# )
|
||||
|
||||
## Mark other files for installation (e.g. launch and bag files, etc.)
|
||||
# install(FILES
|
||||
# # myfile1
|
||||
# # myfile2
|
||||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||
# )
|
||||
|
||||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
## Add gtest based cpp test target and link libraries
|
||||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_aliengoAndarm.cpp)
|
||||
# if(TARGET ${PROJECT_NAME}-test)
|
||||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
|
||||
# endif()
|
||||
|
||||
## Add folders to be run by python nosetests
|
||||
# catkin_add_nosetests(test)
|
|
@ -0,0 +1,105 @@
|
|||
aliengoZ1_gazebo:
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 1000
|
||||
|
||||
# FL Controllers ---------------------------------------
|
||||
FL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# FR Controllers ---------------------------------------
|
||||
FR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
FR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
FR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: FR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RL Controllers ---------------------------------------
|
||||
RL_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RL_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RL_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RL_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
# RR Controllers ---------------------------------------
|
||||
RR_hip_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_hip_joint
|
||||
pid: {p: 100.0, i: 0.0, d: 5.0}
|
||||
|
||||
RR_thigh_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_thigh_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
RR_calf_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: RR_calf_joint
|
||||
pid: {p: 300.0, i: 0.0, d: 8.0}
|
||||
|
||||
Joint01_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: joint1
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
||||
Joint02_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: joint2
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
||||
Joint03_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: joint3
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
||||
Joint04_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: joint4
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
||||
Joint05_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: joint5
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
||||
Joint06_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: joint6
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
||||
gripper_controller:
|
||||
type: unitree_legged_control/UnitreeJointController
|
||||
joint: jointGripper
|
||||
pid: {p: 300.0, i: 0.0, d: 5.0}
|
||||
|
|
@ -0,0 +1,74 @@
|
|||
<launch>
|
||||
<arg name="wname" default="earth"/>
|
||||
<arg name="rname" default="aliengoZ1"/>
|
||||
<arg name="robot_path" value="(find $(arg rname)_description)"/>
|
||||
<arg name="dollar" value="$"/>
|
||||
|
||||
<arg name="UnitreeGripperYN" default="true"/>
|
||||
|
||||
<arg name="paused" default="true"/>
|
||||
<arg name="use_sim_time" default="true"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="debug" default="false"/>
|
||||
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
||||
<arg name="user_debug" default="false"/>
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(find unitree_gazebo)/worlds/$(arg wname).world"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
</include>
|
||||
|
||||
<!-- Load the URDF into the ROS Parameter Server -->
|
||||
<param name="robot_description"
|
||||
command="$(find xacro)/xacro --inorder '$(arg dollar)$(arg robot_path)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug)"/>
|
||||
|
||||
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
|
||||
<!-- Set trunk and joint positions at startup -->
|
||||
<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner" respawn="false" output="screen"
|
||||
args="-urdf -z 0.6 -model $(arg rname)_gazebo -param robot_description -unpause"/>
|
||||
|
||||
<!-- Load joint controller configurations from YAML file to parameter server -->
|
||||
<rosparam file="$(arg dollar)$(arg robot_path)/config/robot_control.yaml" command="load"/>
|
||||
|
||||
<!-- load the controllers -->
|
||||
<group unless="$(arg UnitreeGripperYN)">
|
||||
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
|
||||
output="screen" ns="/$(arg rname)_gazebo" args="joint_state_controller
|
||||
Joint01_controller Joint02_controller Joint03_controller
|
||||
Joint04_controller Joint05_controller Joint06_controller
|
||||
FL_hip_controller FL_thigh_controller FL_calf_controller
|
||||
FR_hip_controller FR_thigh_controller FR_calf_controller
|
||||
RL_hip_controller RL_thigh_controller RL_calf_controller
|
||||
RR_hip_controller RR_thigh_controller RR_calf_controller"/>
|
||||
</group>
|
||||
|
||||
<group if="$(arg UnitreeGripperYN)">
|
||||
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
|
||||
output="screen" ns="/$(arg rname)_gazebo" args="joint_state_controller
|
||||
Joint01_controller Joint02_controller Joint03_controller
|
||||
Joint04_controller Joint05_controller Joint06_controller
|
||||
gripper_controller
|
||||
FL_hip_controller FL_thigh_controller FL_calf_controller
|
||||
FR_hip_controller FR_thigh_controller FR_calf_controller
|
||||
RL_hip_controller RL_thigh_controller RL_calf_controller
|
||||
RR_hip_controller RR_thigh_controller RR_calf_controller"/>
|
||||
</group>
|
||||
|
||||
<!-- convert joint states to TF transforms for rviz, etc -->
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
|
||||
respawn="false" output="screen">
|
||||
<remap from="/joint_states" to="/$(arg rname)_gazebo/joint_states"/>
|
||||
</node>
|
||||
|
||||
<!-- load the parameter unitree_controller -->
|
||||
<include file="$(find unitree_controller)/launch/set_ctrl.launch">
|
||||
<arg name="rname" value="$(arg rname)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,21 @@
|
|||
<launch>
|
||||
|
||||
<arg name="user_debug" default="true"/>
|
||||
<arg name="UnitreeGripperYN" default="true"/>
|
||||
|
||||
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find aliengoZ1_description)/xacro/robot.xacro'
|
||||
DEBUG:=$(arg user_debug) UnitreeGripper:=$(arg UnitreeGripperYN)"/>
|
||||
|
||||
<!-- send fake joint values -->
|
||||
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher">
|
||||
<param name="use_gui" value="TRUE"/>
|
||||
</node>
|
||||
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
|
||||
<param name="publish_frequency" type="double" value="1000.0"/>
|
||||
</node>
|
||||
|
||||
<node pkg="rviz" type="rviz" name="rviz" respawn="false" output="screen"
|
||||
args="-d $(find aliengo_description)/launch/check_joint.rviz"/>
|
||||
|
||||
</launch>
|
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
Binary file not shown.
After Width: | Height: | Size: 130 KiB |
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
|
@ -0,0 +1,15 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>aliengoZ1_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The aliengoZ1_description package</description>
|
||||
<maintainer email="laikago@unitree.cc">unitree</maintainer>
|
||||
<license>TODO</license>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>urdf</build_depend>
|
||||
<build_depend>xacro</build_depend>
|
||||
<build_export_depend>urdf</build_export_depend>
|
||||
<build_export_depend>xacro</build_export_depend>
|
||||
<exec_depend>urdf</exec_depend>
|
||||
<exec_depend>xacro</exec_depend>
|
||||
</package>
|
|
@ -0,0 +1,24 @@
|
|||
<?xml version="1.0" ?>
|
||||
<sdf version="1.4">
|
||||
<!-- We use a custom world for the rrbot so that the camera angle is launched correctly -->
|
||||
|
||||
<world name="default">
|
||||
<include>
|
||||
<uri>model://ground_plane</uri>
|
||||
</include>
|
||||
|
||||
<!-- Global light source -->
|
||||
<include>
|
||||
<uri>model://sun</uri>
|
||||
</include>
|
||||
|
||||
<!-- Focus camera on tall pendulum -->
|
||||
<gui fullscreen='0'>
|
||||
<camera name='user_camera'>
|
||||
<pose>4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190</pose>
|
||||
<view_controller>orbit</view_controller>
|
||||
</camera>
|
||||
</gui>
|
||||
|
||||
</world>
|
||||
</sdf>
|
|
@ -0,0 +1,15 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="aliengoZ1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/>
|
||||
|
||||
<!-- the base of arm offset -->
|
||||
<xacro:property name="arm_offset_x" value="${trunk_length/2.0 - 0.07}"/>
|
||||
<xacro:property name="arm_offset_y" value="0"/>
|
||||
<xacro:property name="arm_offset_z" value="${trunk_height/2.0}"/>
|
||||
<xacro:property name="arm_offset_r" value="0"/>
|
||||
<xacro:property name="arm_offset_p" value="0"/>
|
||||
<xacro:property name="arm_offset_yaw" value="0"/>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,281 @@
|
|||
<?xml version="1.0"?>
|
||||
<robot>
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/aliengoZ1_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of trunk center. -->
|
||||
<gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>10</frequency>
|
||||
<plot>
|
||||
<link>base</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Yellow</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
|
||||
<!-- <gazebo>
|
||||
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
|
||||
<frequency>100</frequency>
|
||||
<plot>
|
||||
<link>FL_foot</link>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<material>Gazebo/Green</material>
|
||||
</plot>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
|
||||
<bodyName>trunk</bodyName>
|
||||
<topicName>/apply_force/trunk</topicName>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<gravity>true</gravity>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>1000</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>__default_topic__</topic>
|
||||
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
|
||||
<topicName>trunk_imu</topicName>
|
||||
<bodyName>imu_link</bodyName>
|
||||
<updateRateHZ>1000.0</updateRateHZ>
|
||||
<gaussianNoise>0.0</gaussianNoise>
|
||||
<xyzOffset>0 0 0</xyzOffset>
|
||||
<rpyOffset>0 0 0</rpyOffset>
|
||||
<frameName>imu_link</frameName>
|
||||
</plugin>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Foot contacts. -->
|
||||
<gazebo reference="FR_calf">
|
||||
<sensor name="FR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<sensor name="FL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<sensor name="RR_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<sensor name="RL_foot_contact" type="contact">
|
||||
<update_rate>100</update_rate>
|
||||
<plugin name="contactPlugin" filename="libunitreeFootContactPlugin.so"/>
|
||||
<contact>
|
||||
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- Visualization of Foot contacts. -->
|
||||
<gazebo reference="FR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>FL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RR_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<visual>
|
||||
<plugin name="drawForcePlugin" filename="libunitreeDrawForcePlugin.so">
|
||||
<topicName>RL_foot_contact</topicName>
|
||||
</plugin>
|
||||
</visual>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="base">
|
||||
<material>Gazebo/Green</material>
|
||||
<turnGravityOff>false</turnGravityOff>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="trunk">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="stick_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/White</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="imu_link">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- FL leg -->
|
||||
<gazebo reference="FL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- FR leg -->
|
||||
<gazebo reference="FR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="FR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RL leg -->
|
||||
<gazebo reference="RL_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RL_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- RR leg -->
|
||||
<gazebo reference="RR_hip">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_thigh">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_calf">
|
||||
<mu1>0.2</mu1>
|
||||
<mu2>0.2</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="RR_foot">
|
||||
<mu1>0.6</mu1>
|
||||
<mu2>0.6</mu2>
|
||||
<self_collide>1</self_collide>
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
<kp value="1000000.0"/>
|
||||
<kd value="1.0"/>
|
||||
</gazebo>
|
||||
|
||||
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo reference="link04">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="link05">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="link06">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,416 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="aliengoZ1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="$(find aliengoZ1_description)/xacro/gazebo.xacro"/>
|
||||
<xacro:include filename="$(find aliengoZ1_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/leg.xacro"/>
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find aliengo_description)/xacro/materials.xacro"/>
|
||||
<xacro:include filename="$(find z1_description)/xacro/const.xacro"/>
|
||||
<xacro:include filename="$(find z1_description)/xacro/transmission.xacro"/>
|
||||
|
||||
<xacro:arg name="UnitreeGripper" default="true"/>
|
||||
|
||||
<!-- 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"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
<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"/>
|
||||
<geometry>
|
||||
<mesh filename="package://aliengo_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.000001" 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="trunk_arm_joint" type="fixed">
|
||||
<origin rpy="${arm_offset_r} ${arm_offset_p} ${arm_offset_yaw}" xyz="${arm_offset_x} ${arm_offset_y} ${arm_offset_z}"/>
|
||||
<parent link="trunk"/>
|
||||
<child link="link00"/>
|
||||
</joint>
|
||||
|
||||
<link name="link00">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link00.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${motor_height}" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 ${motor_height/2.0}"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L00_ComX} ${L00_ComY} ${L00_ComZ}"/>
|
||||
<mass value="${L00_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L00_Ixx}" ixy="${L00_Ixy}" ixz="${L00_Ixz}"
|
||||
iyy="${L00_Iyy}" iyz="${L00_Iyz}"
|
||||
izz="${L00_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="joint1" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.0585"/>
|
||||
<parent link="link00"/>
|
||||
<child link="link01"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<dynamics damping="${jointDamping}" friction="${jointFriction}"/>
|
||||
<limit effort="${torqueMax}" velocity="${velocityMax}" lower="${joint1_PositionMin}" upper="${joint1_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="link01">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link01.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<!-- <collision>
|
||||
<geometry>
|
||||
<cylinder length="${2*motor_height}" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L01_ComX} ${L01_ComY} ${L01_ComZ}"/>
|
||||
<mass value="${L01_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L01_Ixx}" ixy="${L01_Ixy}" ixz="${L01_Ixz}"
|
||||
iyy="${L01_Iyy}" iyz="${L01_Iyz}"
|
||||
izz="${L01_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="joint2" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.045"/>
|
||||
<parent link="link01"/>
|
||||
<child link="link02"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${2*jointDamping}" friction="${2*jointFriction}"/>
|
||||
<limit effort="${2*torqueMax}" velocity="${velocityMax}" lower="${joint2_PositionMin}" upper="${joint2_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="link02">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link02.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${2.0*motor_height}" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${arm1_height}" radius="${arm1_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="${-0.045-arm1_height/2.0} 0 0"/>
|
||||
</collision>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${motor_height}" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="-0.35 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L02_ComX} ${L02_ComY} ${L02_ComZ}"/>
|
||||
<mass value="${L02_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L02_Ixx}" ixy="${L02_Ixy}" ixz="${L02_Ixz}"
|
||||
iyy="${L02_Iyy}" iyz="${L02_Iyz}"
|
||||
izz="${L02_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="joint3" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="-0.35 0 0"/>
|
||||
<parent link="link02"/>
|
||||
<child link="link03"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${jointDamping}" friction="${jointFriction}"/>
|
||||
<limit effort="${torqueMax}" velocity="${velocityMax}" lower="${joint3_PositionMin}" upper="${joint3_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="link03">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link03.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${arm2_height-0.01}" radius="${arm2_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="${0.065+arm2_height/2.0} 0 0.055"/>
|
||||
</collision>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="0.059" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="${0.065+0.185-0.059/2.0} 0 0.055"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L03_ComX} ${L03_ComY} ${L03_ComZ}"/>
|
||||
<mass value="${L03_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L03_Ixx}" ixy="${L03_Ixy}" ixz="${L03_Ixz}"
|
||||
iyy="${L03_Iyy}" iyz="${L03_Iyz}"
|
||||
izz="${L03_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="joint4" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.218 0 0.057"/>
|
||||
<parent link="link03"/>
|
||||
<child link="link04"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${jointDamping}" friction="${jointFriction}"/>
|
||||
<limit effort="${torqueMax}" velocity="${velocityMax}" lower="${joint4_PositionMin}" upper="${joint4_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="link04">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link04.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="0.073" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0.0472 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L04_ComX} ${L04_ComY} ${L04_ComZ}"/>
|
||||
<mass value="${L04_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L04_Ixx}" ixy="${L04_Ixy}" ixz="${L04_Ixz}"
|
||||
iyy="${L04_Iyy}" iyz="${L04_Iyz}"
|
||||
izz="${L04_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="joint5" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.07 0.0 0.0"/>
|
||||
<parent link="link04"/>
|
||||
<child link="link05"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<dynamics damping="${jointDamping}" friction="${jointFriction}"/>
|
||||
<limit effort="${torqueMax}" velocity="${velocityMax}" lower="${joint5_PositionMin}" upper="${joint5_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="link05">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link05.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L05_ComX} ${L05_ComY} ${L05_ComZ}"/>
|
||||
<mass value="${L05_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L05_Ixx}" ixy="${L05_Ixy}" ixz="${L05_Ixz}"
|
||||
iyy="${L05_Iyy}" iyz="${L05_Iyz}"
|
||||
izz="${L05_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="joint6" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.0492 0.0 0.0"/>
|
||||
<parent link="link05"/>
|
||||
<child link="link06"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="${jointDamping}" friction="${jointFriction}"/>
|
||||
<limit effort="${torqueMax}" velocity="${velocityMax}" lower="${joint6_PositionMin}" upper="${joint6_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="link06">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_Link06.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="${motor_height}" radius="${motor_diameter}"/>
|
||||
</geometry>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="${motor_height/2.0} 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${L06_ComX} ${L06_ComY} ${L06_ComZ}"/>
|
||||
<mass value="${L06_Mass}"/>
|
||||
<inertia
|
||||
ixx="${L06_Ixx}" ixy="${L06_Ixy}" ixz="${L06_Ixz}"
|
||||
iyy="${L06_Iyy}" iyz="${L06_Iyz}"
|
||||
izz="${L06_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="$(arg UnitreeGripper)">
|
||||
<joint name="gripperStator" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.051 0.0 0.0"/>
|
||||
<parent link="link06"/>
|
||||
<child link="gripperStator"/>
|
||||
</joint>
|
||||
|
||||
<link name="gripperStator">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_GripperStator.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/collision/z1_GripperStator.STL" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${GripperStator_ComX} ${GripperStator_ComY} ${GripperStator_ComZ}"/>
|
||||
<mass value="${GripperStator_Mass}"/>
|
||||
<inertia
|
||||
ixx="${GripperStator_Ixx}" ixy="${GripperStator_Ixy}" ixz="${GripperStator_Ixz}"
|
||||
iyy="${GripperStator_Iyy}" iyz="${GripperStator_Iyz}"
|
||||
izz="${GripperStator_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="jointGripper" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.049 0.0 0"/>
|
||||
<parent link="gripperStator"/>
|
||||
<child link="gripperMover"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="${jointDamping}" friction="${jointFriction}"/>
|
||||
<limit effort="${torqueMax}" velocity="${velocityMax}" lower="${Gripper_PositionMin}" upper="${Gripper_PositionMax}"/>
|
||||
</joint>
|
||||
|
||||
<link name="gripperMover">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/visual/z1_GripperMover.dae" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://z1_description/meshes/collision/z1_GripperMover.STL" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${GripperMover_ComX} ${GripperMover_ComY} ${GripperMover_ComZ}"/>
|
||||
<mass value="${GripperMover_Mass}"/>
|
||||
<inertia
|
||||
ixx="${GripperMover_Ixx}" ixy="${GripperMover_Ixy}" ixz="${GripperMover_Ixz}"
|
||||
iyy="${GripperMover_Iyy}" iyz="${GripperMover_Iyz}"
|
||||
izz="${GripperMover_Izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:motorTransmission name="Gripper"/>
|
||||
|
||||
<gazebo reference="gripperStator">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="gripperMover">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:motorTransmission name="1"/>
|
||||
<xacro:motorTransmission name="2"/>
|
||||
<xacro:motorTransmission name="3"/>
|
||||
<xacro:motorTransmission name="4"/>
|
||||
<xacro:motorTransmission name="5"/>
|
||||
<xacro:motorTransmission name="6"/>
|
||||
|
||||
<xacro:leg name="FR" mirror="-1" mirror_dae= "False" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True">
|
||||
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False">
|
||||
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||
</xacro:leg>
|
||||
|
||||
</robot>
|
|
@ -0,0 +1,46 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:property name="stair_length" value="0.640" />
|
||||
<xacro:property name="stair_width" value="0.310" />
|
||||
<xacro:property name="stair_height" value="0.170" />
|
||||
|
||||
<xacro:macro name="stairs" params="stairs xpos ypos zpos">
|
||||
|
||||
<joint name="stair_joint_origin" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="stair_link_${stairs}"/>
|
||||
</joint>
|
||||
|
||||
<link name="stair_link_${stairs}">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
<origin rpy="0 0 0" xyz="${xpos} ${ypos} ${zpos}"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="${stair_length} ${stair_width} ${stair_height}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.80"/>
|
||||
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:if value="${stairs}">
|
||||
<xacro:stairs stairs="${stairs-1}" xpos="0" ypos="${ypos-stair_width/2}" zpos="${zpos+stair_height}"/>
|
||||
<joint name="stair_joint_${stairs}" type="fixed">
|
||||
<parent link="stair_link_${stairs}"/>
|
||||
<child link="stair_link_${stairs-1}"/>
|
||||
</joint>
|
||||
</xacro:if>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
Loading…
Reference in New Issue