Merge 4b100ef258
into bb131e11f9
This commit is contained in:
commit
6fe96438ba
|
@ -0,0 +1,346 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from src/unitree_ros/robots/z1_description/xacro/robot.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="z1_description">
|
||||
<!-- ros_control plugin -->
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
|
||||
<robotNamespace>/z1_gazebo</robotNamespace>
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<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>
|
||||
<link name="world"/>
|
||||
<joint name="base_static_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<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="0.051" radius="0.0325"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.0255"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00334984 -0.00013615 0.02495843"/>
|
||||
<mass value="0.47247481"/>
|
||||
<inertia ixx="0.00037937" ixy="3.5e-07" ixz="1.037e-05" iyy="0.00041521" iyz="9.9e-07" izz="0.00053066"/>
|
||||
</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="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-2.6179938779914944" upper="2.6179938779914944" velocity="10"/>
|
||||
</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="2.47e-06 -0.00025198 0.02317169"/>
|
||||
<mass value="0.67332551"/>
|
||||
<inertia ixx="0.00128328" ixy="6e-08" ixz="4e-07" iyy="0.00071931" iyz="-5e-07" izz="0.00083936"/>
|
||||
</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.0" friction="2.0"/>
|
||||
<limit effort="60.0" lower="0.0" upper="3.141592653589793" velocity="10"/>
|
||||
</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="0.102" radius="0.0325"/>
|
||||
</geometry>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="0.235" radius="0.0225"/>
|
||||
</geometry>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="-0.16249999999999998 0 0"/>
|
||||
</collision>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="0.051" radius="0.0325"/>
|
||||
</geometry>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="-0.35 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.11012601 0.00240029 0.00158266"/>
|
||||
<mass value="1.19132258"/>
|
||||
<inertia ixx="0.00102138" ixy="-0.00062358" ixz="-5.13e-06" iyy="0.02429457" iyz="2.1e-06" izz="0.02466114"/>
|
||||
</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="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-4.782202150464463" upper="0.0" velocity="10"/>
|
||||
</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="0.116" radius="0.02"/>
|
||||
</geometry>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0.128 0 0.055"/>
|
||||
</collision>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="0.059" radius="0.0325"/>
|
||||
</geometry>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0.2205 0 0.055"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.10609208 -0.00541815 0.03476383"/>
|
||||
<mass value="0.83940874"/>
|
||||
<inertia ixx="0.00108061" ixy="8.669e-05" ixz="0.00208102" iyy="0.00954238" iyz="1.332e-05" izz="0.00886621"/>
|
||||
</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="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-1.7453292519943295" upper="1.5707963267948966" velocity="10"/>
|
||||
</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="0.0325"/>
|
||||
</geometry>
|
||||
<origin rpy="1.5707963267948966 0 0" xyz="0.0472 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.04366681 0.00364738 -0.00170192"/>
|
||||
<mass value="0.56404563"/>
|
||||
<inertia ixx="0.00031576" ixy="-8.13e-05" ixz="-4.091e-05" iyy="0.00092996" iyz="5.96e-06" izz="0.00097912"/>
|
||||
</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="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-1.7278759594743864" upper="1.7278759594743864" velocity="10"/>
|
||||
</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="0.03121533 0.0 0.00646316"/>
|
||||
<mass value="0.38938492"/>
|
||||
<inertia ixx="0.00017605" ixy="-4e-07" ixz="-5.689e-05" iyy="0.00055896" iyz="1.3e-07" izz="0.0005386"/>
|
||||
</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="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-2.792526803190927" upper="2.792526803190927" velocity="10"/>
|
||||
</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="0.051" radius="0.0325"/>
|
||||
</geometry>
|
||||
<origin rpy="0 1.5707963267948966 0" xyz="0.0255 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0241569 -0.00017355 -0.00143876"/>
|
||||
<mass value="0.28875807"/>
|
||||
<inertia ixx="0.00018328" ixy="-1.22e-06" ixz="-5.4e-07" iyy="0.0001475" iyz="-8e-08" izz="0.0001468"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<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="0.04764427 -0.00035819 -0.00249162"/>
|
||||
<mass value="0.52603655"/>
|
||||
<inertia ixx="0.00038683" ixy="3.59e-06" ixz="-7.662e-05" iyy="0.00068614" iyz="-2.09e-06" izz="0.00066293"/>
|
||||
</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="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-1.5707963267948966" upper="0.0" velocity="10"/>
|
||||
</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="0.01320633 0.00476708 0.00380534"/>
|
||||
<mass value="0.27621302"/>
|
||||
<inertia ixx="0.00017716" ixy="-1.683e-05" ixz="1.786e-05" iyy="0.00026787" iyz="-2.62e-06" izz="0.00035728"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="JointTransGripper">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="jointGripper">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="ActuatorGripper">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<gazebo reference="gripperStator">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
<gazebo reference="gripperMover">
|
||||
<self_collide>true</self_collide>
|
||||
</gazebo>
|
||||
<transmission name="JointTrans1">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint1">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Actuator1">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="JointTrans2">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint2">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Actuator2">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="JointTrans3">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint3">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Actuator3">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="JointTrans4">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint4">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Actuator4">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="JointTrans5">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint5">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Actuator5">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="JointTrans6">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint6">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="Actuator6">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</robot>
|
||||
|
|
@ -1,4 +1,4 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
cmake_minimum_required(VERSION 3.0)
|
||||
project(unitree_controller)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
|
@ -29,6 +29,8 @@ include_directories(
|
|||
)
|
||||
|
||||
link_directories(${GAZEBO_LIBRARY_DIRS})
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
|
||||
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
|
||||
|
||||
# Declare a C++ library
|
||||
|
@ -55,4 +57,4 @@ add_executable(unitree_servo src/servo.cpp)
|
|||
target_link_libraries(unitree_servo ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(unitree_move_kinetic src/move_publisher.cpp)
|
||||
target_link_libraries(unitree_move_kinetic ${catkin_LIBRARIES})
|
||||
target_link_libraries(unitree_move_kinetic ${catkin_LIBRARIES})
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
<launch>
|
||||
<arg name="wname" default="earth"/>
|
||||
<arg name="rname" default="z1"/>
|
||||
<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'
|
||||
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.0 -model $(arg rname)_gazebo -param robot_description -unpause"/> -->
|
||||
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,51 @@
|
|||
<launch>
|
||||
<arg name="wname" default="earth"/>
|
||||
<arg name="rname" default="z1"/>
|
||||
<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"/>
|
||||
|
||||
<param name="robot_description"
|
||||
command="$(find xacro)/xacro --inorder '$(arg dollar)$(arg robot_path)/xacro/robot.xacro'
|
||||
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.0 -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"/>
|
||||
</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"/>
|
||||
</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>
|
||||
|
||||
</launch>
|
|
@ -1,4 +1,4 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
cmake_minimum_required(VERSION 3.0.1)
|
||||
project(unitree_legged_control)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
|
@ -8,6 +8,7 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
roscpp
|
||||
realtime_tools
|
||||
unitree_legged_msgs
|
||||
urdf
|
||||
)
|
||||
|
||||
catkin_package(
|
||||
|
@ -17,16 +18,19 @@ catkin_package(
|
|||
hardware_interface
|
||||
pluginlib
|
||||
roscpp
|
||||
urdf
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES ${PROJECT_NAME}
|
||||
)
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
|
||||
|
||||
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR})
|
||||
|
||||
link_directories($(catkin_LIB_DIRS) lib)
|
||||
link_directories(${catkin_LIB_DIRS} lib)
|
||||
|
||||
add_library( unitree_legged_control
|
||||
src/joint_controller.cpp
|
||||
)
|
||||
add_dependencies(${PROJECT_NAME} unitree_legged_msgs_gencpp)
|
||||
target_link_libraries(unitree_legged_control ${catkin_LIBRARIES} unitree_joint_control_tool)
|
||||
# target_link_libraries(unitree_legged_control ${catkin_LIBRARIES} unitree_joint_control_tool_arm64)
|
||||
target_link_libraries(unitree_legged_control ${catkin_LIBRARIES} unitree_joint_control_tool_${CMAKE_HOST_SYSTEM_PROCESSOR})
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -10,6 +10,7 @@
|
|||
<build_depend>hardware_interface</build_depend>
|
||||
<build_depend>pluginlib</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>urdf</build_depend>
|
||||
<build_export_depend>controller_interface</build_export_depend>
|
||||
<build_export_depend>hardware_interface</build_export_depend>
|
||||
<build_export_depend>pluginlib</build_export_depend>
|
||||
|
@ -18,6 +19,7 @@
|
|||
<exec_depend>hardware_interface</exec_depend>
|
||||
<exec_depend>pluginlib</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>urdf</exec_depend>
|
||||
<depend>unitree_legged_msgs</depend>
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(z1_controller)
|
||||
|
||||
#set(CMAKE_OSX_ARCHITECTURES "x86_64" CACHE INTERNAL "" FORCE)
|
||||
find_package(gazebo REQUIRED)
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
controller_manager
|
||||
|
@ -26,6 +26,8 @@ include_directories(
|
|||
)
|
||||
|
||||
link_directories(${GAZEBO_LIBRARY_DIRS})
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
|
||||
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
|
||||
|
||||
add_library(${PROJECT_NAME}
|
||||
|
@ -39,4 +41,4 @@ target_link_libraries(${PROJECT_NAME}
|
|||
)
|
||||
|
||||
add_executable(unitree_move_z1 src/basic.cpp)
|
||||
target_link_libraries(unitree_move_z1 ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
target_link_libraries(unitree_move_z1 ${PROJECT_NAME} ${catkin_LIBRARIES})
|
||||
|
|
Loading…
Reference in New Issue