Add b1z1_description package

This commit is contained in:
Paul 2024-04-29 17:42:46 -04:00
parent 3435263d52
commit 9f3e0710db
8 changed files with 550 additions and 0 deletions

View File

@ -0,0 +1,4 @@
cmake_minimum_required(VERSION 3.0.2)
project(b1z1_description)
find_package(catkin REQUIRED)

View File

@ -0,0 +1,105 @@
b1z1_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}
# Z1 Controllers ---------------------------------------
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}

View File

@ -0,0 +1,73 @@
<launch>
<arg name="wname" default="earth"/>
<arg name="rname" default="b1z1"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>
<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"/>
<arg name="UnitreeGripperYN" default="true"/>
<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) UnitreeGripper:=$(arg UnitreeGripperYN)"/>
<!-- 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.75 -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>

View File

@ -0,0 +1,18 @@
<launch>
<arg name="user_debug" default="false"/>
<arg name="UnitreeGripperYN" default="true"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find b1z1_description)/xacro/robot.xacro'
DEBUG:=$(arg user_debug) UnitreeGripper:=$(arg UnitreeGripperYN)"/>
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher"/>
<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 b1_description)/launch/check_joint.rviz"/>
</launch>

View File

@ -0,0 +1,12 @@
<?xml version="1.0"?>
<package format="2">
<name>b1z1_description</name>
<version>0.0.0</version>
<description>The b1z1_description package</description>
<maintainer email="b1@unitree.cc">unitree</maintainer>
<license>TODO</license>
<buildtool_depend>catkin</buildtool_depend>
</package>

View File

@ -0,0 +1,17 @@
<?xml version="1.0"?>
<!-- configurable constant parameters for b1z1_description -->
<robot name="b1z1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- include B1 constants -->
<xacro:include filename="$(find b1_description)/xacro/const.xacro"/>
<!-- Z1 mounting point with respect to B1 trunk -->
<xacro:property name="arm_offset_x" value="${hip_offset_x}"/>
<xacro:property name="arm_offset_y" value="0"/>
<xacro:property name="arm_offset_z" value="${trunk_height/2.0 + 0.01}"/>
<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>

View File

@ -0,0 +1,279 @@
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/b1z1_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>
<!-- Z1 arm -->
<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>

View File

@ -0,0 +1,42 @@
<?xml version="1.0"?>
<!-- b1z1_description: B1 quadruped mounted with Z1 robotic arm -->
<robot name="b1z1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- define arguments -->
<xacro:arg name="DEBUG" default="false"/> <!-- debug mode switch -->
<xacro:arg name="UnitreeGripper" default="true"/> <!-- include Z1 end-effector -->
<!-- include xacro files -->
<xacro:include filename="$(find b1_description)/xacro/b1.xacro"/>
<xacro:include filename="$(find z1_description)/xacro/z1.xacro"/>
<xacro:include filename="$(find b1z1_description)/xacro/const.xacro"/>
<xacro:include filename="$(find b1z1_description)/xacro/gazebo.xacro"/>
<!-- B1 macro: expands to describe B1 quadruped -->
<xacro:b1/>
<!-- Z1 macro: expands to describe Z1 robotic arm -->
<xacro:z1 UnitreeGripper="$(arg UnitreeGripper)"/>
<!-- define joint affixing Z1 to B1 -->
<joint name="trunk_arm_joint" type="fixed">
<!-- Z1 mounting point wrt B1 trunk; configurable in const.xacro -->
<origin rpy="${arm_offset_r} ${arm_offset_p} ${arm_offset_yaw}" xyz="${arm_offset_x} ${arm_offset_y} ${arm_offset_z}"/>
<!-- define parent and child links -->
<parent link="trunk"/>
<child link="link00"/>
</joint>
<!-- debug mode configuration -->
<xacro:if value="$(arg DEBUG)">
<!-- debug mode hangs up the robot; i.e., statically affixes B1 base to world -->
<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>
</robot>