add support for aliengo
This commit is contained in:
parent
c4262b42da
commit
2052b3e9d1
|
@ -0,0 +1,11 @@
|
||||||
|
cmake_minimum_required(VERSION 3.8)
|
||||||
|
project(aliengo_description)
|
||||||
|
|
||||||
|
find_package(ament_cmake REQUIRED)
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY meshes xacro launch config
|
||||||
|
DESTINATION share/${PROJECT_NAME}/
|
||||||
|
)
|
||||||
|
|
||||||
|
ament_package()
|
|
@ -0,0 +1,25 @@
|
||||||
|
# Unitree AlienGo Description
|
||||||
|
This repository contains the urdf model of Aliengo.
|
||||||
|
|
||||||
|
Tested environment:
|
||||||
|
* Ubuntu 24.04
|
||||||
|
* ROS2 Jazzy
|
||||||
|
|
||||||
|
## Build
|
||||||
|
```bash
|
||||||
|
cd ~/ros2_ws
|
||||||
|
colcon build --packages-up-to aliengo_description
|
||||||
|
```
|
||||||
|
|
||||||
|
## Visualize the robot
|
||||||
|
To visualize and check the configuration of the robot in rviz, simply launch:
|
||||||
|
```bash
|
||||||
|
source ~/ros2_ws/install/setup.bash
|
||||||
|
ros2 launch aliengo_description visualize.launch.py
|
||||||
|
```
|
||||||
|
|
||||||
|
## Launch Hardware Interface
|
||||||
|
```bash
|
||||||
|
source ~/ros2_ws/install/setup.bash
|
||||||
|
ros2 launch aliengo_description hardware.launch.py
|
||||||
|
```
|
|
@ -0,0 +1,122 @@
|
||||||
|
# Controller Manager configuration
|
||||||
|
controller_manager:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 500 # Hz
|
||||||
|
|
||||||
|
# Define the available controllers
|
||||||
|
joint_state_broadcaster:
|
||||||
|
type: joint_state_broadcaster/JointStateBroadcaster
|
||||||
|
|
||||||
|
imu_sensor_broadcaster:
|
||||||
|
type: imu_sensor_broadcaster/IMUSensorBroadcaster
|
||||||
|
|
||||||
|
unitree_guide_controller:
|
||||||
|
type: unitree_guide_controller/UnitreeGuideController
|
||||||
|
|
||||||
|
ocs2_quadruped_controller:
|
||||||
|
type: ocs2_quadruped_controller/Ocs2QuadrupedController
|
||||||
|
|
||||||
|
imu_sensor_broadcaster:
|
||||||
|
ros__parameters:
|
||||||
|
sensor_name: "imu_sensor"
|
||||||
|
frame_id: "imu_link"
|
||||||
|
|
||||||
|
unitree_guide_controller:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 500 # Hz
|
||||||
|
joints:
|
||||||
|
- FR_hip_joint
|
||||||
|
- FR_thigh_joint
|
||||||
|
- FR_calf_joint
|
||||||
|
- FL_hip_joint
|
||||||
|
- FL_thigh_joint
|
||||||
|
- FL_calf_joint
|
||||||
|
- RR_hip_joint
|
||||||
|
- RR_thigh_joint
|
||||||
|
- RR_calf_joint
|
||||||
|
- RL_hip_joint
|
||||||
|
- RL_thigh_joint
|
||||||
|
- RL_calf_joint
|
||||||
|
|
||||||
|
command_interfaces:
|
||||||
|
- effort
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
- kp
|
||||||
|
- kd
|
||||||
|
|
||||||
|
state_interfaces:
|
||||||
|
- effort
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
|
||||||
|
feet_names:
|
||||||
|
- FR_foot
|
||||||
|
- FL_foot
|
||||||
|
- RR_foot
|
||||||
|
- RL_foot
|
||||||
|
|
||||||
|
imu_name: "imu_sensor"
|
||||||
|
base_name: "base"
|
||||||
|
|
||||||
|
imu_interfaces:
|
||||||
|
- orientation.w
|
||||||
|
- orientation.x
|
||||||
|
- orientation.y
|
||||||
|
- orientation.z
|
||||||
|
- angular_velocity.x
|
||||||
|
- angular_velocity.y
|
||||||
|
- angular_velocity.z
|
||||||
|
- linear_acceleration.x
|
||||||
|
- linear_acceleration.y
|
||||||
|
- linear_acceleration.z
|
||||||
|
|
||||||
|
ocs2_quadruped_controller:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 500 # Hz
|
||||||
|
joints:
|
||||||
|
- FR_hip_joint
|
||||||
|
- FR_thigh_joint
|
||||||
|
- FR_calf_joint
|
||||||
|
- FL_hip_joint
|
||||||
|
- FL_thigh_joint
|
||||||
|
- FL_calf_joint
|
||||||
|
- RR_hip_joint
|
||||||
|
- RR_thigh_joint
|
||||||
|
- RR_calf_joint
|
||||||
|
- RL_hip_joint
|
||||||
|
- RL_thigh_joint
|
||||||
|
- RL_calf_joint
|
||||||
|
|
||||||
|
command_interfaces:
|
||||||
|
- effort
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
- kp
|
||||||
|
- kd
|
||||||
|
|
||||||
|
state_interfaces:
|
||||||
|
- effort
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
|
||||||
|
feet_names:
|
||||||
|
- FR_foot
|
||||||
|
- FL_foot
|
||||||
|
- RR_foot
|
||||||
|
- RL_foot
|
||||||
|
|
||||||
|
imu_name: "imu_sensor"
|
||||||
|
base_name: "base"
|
||||||
|
|
||||||
|
imu_interfaces:
|
||||||
|
- orientation.w
|
||||||
|
- orientation.x
|
||||||
|
- orientation.y
|
||||||
|
- orientation.z
|
||||||
|
- angular_velocity.x
|
||||||
|
- angular_velocity.y
|
||||||
|
- angular_velocity.z
|
||||||
|
- linear_acceleration.x
|
||||||
|
- linear_acceleration.y
|
||||||
|
- linear_acceleration.z
|
|
@ -0,0 +1,383 @@
|
||||||
|
Panels:
|
||||||
|
- Class: rviz_common/Displays
|
||||||
|
Help Height: 138
|
||||||
|
Name: Displays
|
||||||
|
Property Tree Widget:
|
||||||
|
Expanded:
|
||||||
|
- /Global Options1
|
||||||
|
- /Status1
|
||||||
|
- /RobotModel1
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Tree Height: 303
|
||||||
|
- Class: rviz_common/Selection
|
||||||
|
Name: Selection
|
||||||
|
- Class: rviz_common/Tool Properties
|
||||||
|
Expanded:
|
||||||
|
- /2D Goal Pose1
|
||||||
|
- /Publish Point1
|
||||||
|
Name: Tool Properties
|
||||||
|
Splitter Ratio: 0.5886790156364441
|
||||||
|
- Class: rviz_common/Views
|
||||||
|
Expanded:
|
||||||
|
- /Current View1
|
||||||
|
Name: Views
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
- Class: rviz_common/Time
|
||||||
|
Experimental: false
|
||||||
|
Name: Time
|
||||||
|
SyncMode: 0
|
||||||
|
SyncSource: ""
|
||||||
|
Visualization Manager:
|
||||||
|
Class: ""
|
||||||
|
Displays:
|
||||||
|
- Alpha: 0.5
|
||||||
|
Cell Size: 1
|
||||||
|
Class: rviz_default_plugins/Grid
|
||||||
|
Color: 160; 160; 164
|
||||||
|
Enabled: true
|
||||||
|
Line Style:
|
||||||
|
Line Width: 0.029999999329447746
|
||||||
|
Value: Lines
|
||||||
|
Name: Grid
|
||||||
|
Normal Cell Count: 0
|
||||||
|
Offset:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Plane: XY
|
||||||
|
Plane Cell Count: 10
|
||||||
|
Reference Frame: <Fixed Frame>
|
||||||
|
Value: true
|
||||||
|
- Alpha: 1
|
||||||
|
Class: rviz_default_plugins/RobotModel
|
||||||
|
Collision Enabled: false
|
||||||
|
Description File: ""
|
||||||
|
Description Source: Topic
|
||||||
|
Description Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /robot_description
|
||||||
|
Enabled: true
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
FL_calf:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FL_calf_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FL_foot:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FL_hip:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FL_hip_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FL_thigh:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FL_thigh_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_calf:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_calf_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_foot:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_hip:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_hip_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_thigh:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
FR_thigh_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
RL_calf:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RL_calf_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RL_foot:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RL_hip:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RL_hip_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RL_thigh:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RL_thigh_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_calf:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_calf_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_foot:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_hip:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_hip_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_thigh:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
RR_thigh_rotor:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
base:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
camera_chin:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
camera_face:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
camera_laserscan_link_left:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_laserscan_link_right:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_left:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
camera_optical_chin:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_optical_face:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_optical_left:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_optical_rearDown:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_optical_right:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
camera_rearDown:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
camera_right:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
imu_link:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
trunk:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
ultraSound_face:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
ultraSound_left:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
ultraSound_right:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
Mass Properties:
|
||||||
|
Inertia: false
|
||||||
|
Mass: false
|
||||||
|
Name: RobotModel
|
||||||
|
TF Prefix: ""
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
Visual Enabled: true
|
||||||
|
Enabled: true
|
||||||
|
Global Options:
|
||||||
|
Background Color: 48; 48; 48
|
||||||
|
Fixed Frame: base
|
||||||
|
Frame Rate: 30
|
||||||
|
Name: root
|
||||||
|
Tools:
|
||||||
|
- Class: rviz_default_plugins/Interact
|
||||||
|
Hide Inactive Objects: true
|
||||||
|
- Class: rviz_default_plugins/MoveCamera
|
||||||
|
- Class: rviz_default_plugins/Select
|
||||||
|
- Class: rviz_default_plugins/FocusCamera
|
||||||
|
- Class: rviz_default_plugins/Measure
|
||||||
|
Line color: 128; 128; 0
|
||||||
|
- Class: rviz_default_plugins/SetInitialPose
|
||||||
|
Covariance x: 0.25
|
||||||
|
Covariance y: 0.25
|
||||||
|
Covariance yaw: 0.06853891909122467
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /initialpose
|
||||||
|
- Class: rviz_default_plugins/SetGoal
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /goal_pose
|
||||||
|
- Class: rviz_default_plugins/PublishPoint
|
||||||
|
Single click: true
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /clicked_point
|
||||||
|
Transformation:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/TF
|
||||||
|
Value: true
|
||||||
|
Views:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/Orbit
|
||||||
|
Distance: 0.8687032461166382
|
||||||
|
Enable Stereo Rendering:
|
||||||
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
|
Stereo Focal Distance: 1
|
||||||
|
Swap Stereo Eyes: false
|
||||||
|
Value: false
|
||||||
|
Focal Point:
|
||||||
|
X: 0.017344314604997635
|
||||||
|
Y: -0.0033522010780870914
|
||||||
|
Z: -0.09058035165071487
|
||||||
|
Focal Shape Fixed Size: true
|
||||||
|
Focal Shape Size: 0.05000000074505806
|
||||||
|
Invert Z Axis: false
|
||||||
|
Name: Current View
|
||||||
|
Near Clip Distance: 0.009999999776482582
|
||||||
|
Pitch: 0.49539798498153687
|
||||||
|
Target Frame: <Fixed Frame>
|
||||||
|
Value: Orbit (rviz)
|
||||||
|
Yaw: 0.8403961062431335
|
||||||
|
Saved: ~
|
||||||
|
Window Geometry:
|
||||||
|
Displays:
|
||||||
|
collapsed: true
|
||||||
|
Height: 630
|
||||||
|
Hide Left Dock: true
|
||||||
|
Hide Right Dock: true
|
||||||
|
QMainWindow State: 000000ff00000000fd0000000400000000000001f40000043cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000700000043c000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000043cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000043c000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003130000005efc0100000002fb0000000800540069006d0065010000000000000313000002fb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000313000001b800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
|
Selection:
|
||||||
|
collapsed: false
|
||||||
|
Time:
|
||||||
|
collapsed: false
|
||||||
|
Tool Properties:
|
||||||
|
collapsed: false
|
||||||
|
Views:
|
||||||
|
collapsed: true
|
||||||
|
Width: 787
|
||||||
|
X: 763
|
||||||
|
Y: 351
|
|
@ -0,0 +1,112 @@
|
||||||
|
import os
|
||||||
|
|
||||||
|
import xacro
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
||||||
|
from launch.event_handlers import OnProcessExit
|
||||||
|
from launch.substitutions import PathJoinSubstitution
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
|
||||||
|
package_description = "aliengo_description"
|
||||||
|
|
||||||
|
|
||||||
|
def process_xacro(context):
|
||||||
|
robot_type_value = context.launch_configurations['robot_type']
|
||||||
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
|
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
||||||
|
return (robot_description_config.toxml(), robot_type_value)
|
||||||
|
|
||||||
|
|
||||||
|
def launch_setup(context, *args, **kwargs):
|
||||||
|
(robot_description, robot_type) = process_xacro(context)
|
||||||
|
robot_controllers = PathJoinSubstitution(
|
||||||
|
[
|
||||||
|
FindPackageShare(package_description),
|
||||||
|
"config",
|
||||||
|
"robot_control.yaml",
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
robot_state_publisher = Node(
|
||||||
|
package='robot_state_publisher',
|
||||||
|
executable='robot_state_publisher',
|
||||||
|
name='robot_state_publisher',
|
||||||
|
parameters=[
|
||||||
|
{
|
||||||
|
'publish_frequency': 20.0,
|
||||||
|
'use_tf_static': True,
|
||||||
|
'robot_description': robot_description,
|
||||||
|
'ignore_timestamp': True
|
||||||
|
}
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
controller_manager = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="ros2_control_node",
|
||||||
|
parameters=[robot_controllers],
|
||||||
|
output="both",
|
||||||
|
)
|
||||||
|
|
||||||
|
joint_state_publisher = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["joint_state_broadcaster",
|
||||||
|
"--controller-manager", "/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
imu_sensor_broadcaster = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["imu_sensor_broadcaster",
|
||||||
|
"--controller-manager", "/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
unitree_guide_controller = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["unitree_guide_controller", "--controller-manager", "/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
return [
|
||||||
|
robot_state_publisher,
|
||||||
|
controller_manager,
|
||||||
|
joint_state_publisher,
|
||||||
|
RegisterEventHandler(
|
||||||
|
event_handler=OnProcessExit(
|
||||||
|
target_action=joint_state_publisher,
|
||||||
|
on_exit=[imu_sensor_broadcaster],
|
||||||
|
)
|
||||||
|
),
|
||||||
|
RegisterEventHandler(
|
||||||
|
event_handler=OnProcessExit(
|
||||||
|
target_action=imu_sensor_broadcaster,
|
||||||
|
on_exit=[unitree_guide_controller],
|
||||||
|
)
|
||||||
|
),
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
robot_type_arg = DeclareLaunchArgument(
|
||||||
|
'robot_type',
|
||||||
|
default_value='aliengo',
|
||||||
|
description='Type of the robot'
|
||||||
|
)
|
||||||
|
|
||||||
|
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
robot_type_arg,
|
||||||
|
OpaqueFunction(function=launch_setup),
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
)
|
||||||
|
])
|
|
@ -0,0 +1,66 @@
|
||||||
|
import os
|
||||||
|
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument, OpaqueFunction
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
import xacro
|
||||||
|
|
||||||
|
package_description = "aliengo_description"
|
||||||
|
|
||||||
|
|
||||||
|
def process_xacro(context):
|
||||||
|
robot_type_value = context.launch_configurations['robot_type']
|
||||||
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
|
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
||||||
|
return robot_description_config.toxml()
|
||||||
|
|
||||||
|
|
||||||
|
def launch_setup(context, *args, **kwargs):
|
||||||
|
robot_description = process_xacro(context)
|
||||||
|
return [
|
||||||
|
Node(
|
||||||
|
package='robot_state_publisher',
|
||||||
|
executable='robot_state_publisher',
|
||||||
|
name='robot_state_publisher',
|
||||||
|
output='screen',
|
||||||
|
parameters=[
|
||||||
|
{
|
||||||
|
'publish_frequency': 100.0,
|
||||||
|
'use_tf_static': True,
|
||||||
|
'robot_description': robot_description
|
||||||
|
}
|
||||||
|
],
|
||||||
|
),
|
||||||
|
Node(
|
||||||
|
package='joint_state_publisher_gui',
|
||||||
|
executable='joint_state_publisher_gui',
|
||||||
|
name='joint_state_publisher',
|
||||||
|
output='screen',
|
||||||
|
)
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
robot_type_arg = DeclareLaunchArgument(
|
||||||
|
'robot_type',
|
||||||
|
default_value='aliengo',
|
||||||
|
description='Type of the robot'
|
||||||
|
)
|
||||||
|
|
||||||
|
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
robot_type_arg,
|
||||||
|
OpaqueFunction(function=launch_setup),
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
)
|
||||||
|
])
|
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 |
|
@ -0,0 +1,19 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<package format="2">
|
||||||
|
<name>aliengo_description</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>The aliengo_description package</description>
|
||||||
|
|
||||||
|
<maintainer email="aliengo@unitree.cc">unitree</maintainer>
|
||||||
|
<license>TODO</license>
|
||||||
|
|
||||||
|
<exec_depend>xacro</exec_depend>
|
||||||
|
<exec_depend>joint_state_publisher</exec_depend>
|
||||||
|
<exec_depend>robot_state_publisher</exec_depend>
|
||||||
|
<exec_depend>imu_sensor_broadcaster</exec_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
|
||||||
|
</package>
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,160 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<!-- Constants for robot dimensions -->
|
||||||
|
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||||
|
<xacro:property name="stick_mass" value="0.00001"/>
|
||||||
|
|
||||||
|
<!-- simplified collision value -->
|
||||||
|
<xacro:property name="trunk_width" value="0.150"/>
|
||||||
|
<xacro:property name="trunk_length" value="0.647"/>
|
||||||
|
<xacro:property name="trunk_height" value="0.112"/>
|
||||||
|
<xacro:property name="hip_radius" value="0.046"/>
|
||||||
|
<xacro:property name="hip_length" value="0.0418"/>
|
||||||
|
<xacro:property name="thigh_shoulder_radius" value="0.044"/>
|
||||||
|
<xacro:property name="thigh_shoulder_length" value="0.08"/>
|
||||||
|
<xacro:property name="thigh_width" value="0.0374"/>
|
||||||
|
<xacro:property name="thigh_height" value="0.043"/>
|
||||||
|
<xacro:property name="calf_width" value="0.0208"/>
|
||||||
|
<xacro:property name="calf_height" value="0.016"/>
|
||||||
|
<xacro:property name="foot_radius" value="0.0265"/>
|
||||||
|
<xacro:property name="stick_radius" value="0.01"/>
|
||||||
|
<xacro:property name="stick_length" value="0.2"/>
|
||||||
|
|
||||||
|
<!-- kinematic value -->
|
||||||
|
<xacro:property name="thigh_offset" value="0.0868"/>
|
||||||
|
<xacro:property name="thigh_length" value="0.25"/>
|
||||||
|
<xacro:property name="calf_length" value="0.25"/>
|
||||||
|
|
||||||
|
<!-- leg offset from trunk center value -->
|
||||||
|
<xacro:property name="leg_offset_x" value="0.2407"/>
|
||||||
|
<xacro:property name="leg_offset_y" value="0.051"/>
|
||||||
|
<xacro:property name="trunk_offset_z" value="0.01675"/>
|
||||||
|
<xacro:property name="hip_offset" value="0.083"/>
|
||||||
|
|
||||||
|
<!-- offset of link and rotor locations (left front) -->
|
||||||
|
<xacro:property name="hip_offset_x" value="0.2407"/>
|
||||||
|
<xacro:property name="hip_offset_y" value="0.051"/>
|
||||||
|
<xacro:property name="hip_offset_z" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_offset_x" value="0.139985"/>
|
||||||
|
<xacro:property name="hip_rotor_offset_y" value="0.051"/>
|
||||||
|
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
|
||||||
|
|
||||||
|
<xacro:property name="thigh_offset_x" value="0"/>
|
||||||
|
<xacro:property name="thigh_offset_y" value="0.0868"/>
|
||||||
|
<xacro:property name="thigh_offset_z" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_offset_y" value="0.0298"/>
|
||||||
|
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
|
||||||
|
|
||||||
|
<xacro:property name="calf_offset_x" value="0.0"/>
|
||||||
|
<xacro:property name="calf_offset_y" value="0.0"/>
|
||||||
|
<xacro:property name="calf_offset_z" value="-0.25"/>
|
||||||
|
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_offset_y" value="-0.0997"/>
|
||||||
|
<xacro:property name="calf_rotor_offset_z" value="0.0"/>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- joint limits -->
|
||||||
|
<xacro:property name="damping" value="0"/>
|
||||||
|
<xacro:property name="friction" value="0"/>
|
||||||
|
<xacro:property name="hip_position_max" value="${70*PI/180.0}"/>
|
||||||
|
<xacro:property name="hip_position_min" value="${-70*PI/180.0}"/>
|
||||||
|
<xacro:property name="hip_velocity_max" value="20"/>
|
||||||
|
<xacro:property name="hip_torque_max" value="35.278"/>
|
||||||
|
<xacro:property name="thigh_position_max" value="${240*PI/180.0}"/>
|
||||||
|
<xacro:property name="thigh_position_min" value="${-120*PI/180.0}"/>
|
||||||
|
<xacro:property name="thigh_velocity_max" value="20"/>
|
||||||
|
<xacro:property name="thigh_torque_max" value="35.278"/>
|
||||||
|
<xacro:property name="calf_position_max" value="${-37*PI/180.0}"/>
|
||||||
|
<xacro:property name="calf_position_min" value="${-159*PI/180.0}"/>
|
||||||
|
<xacro:property name="calf_velocity_max" value="15.89"/>
|
||||||
|
<xacro:property name="calf_torque_max" value="44.4"/>
|
||||||
|
|
||||||
|
<!-- dynamics inertial value total 23.0kg -->
|
||||||
|
<!-- trunk -->
|
||||||
|
<xacro:property name="trunk_mass" value="11.644"/>
|
||||||
|
<xacro:property name="trunk_com_x" value="0.008811"/>
|
||||||
|
<xacro:property name="trunk_com_y" value="0.003839"/>
|
||||||
|
<xacro:property name="trunk_com_z" value="0.000273"/>
|
||||||
|
<xacro:property name="trunk_ixx" value="0.051944892"/>
|
||||||
|
<xacro:property name="trunk_ixy" value="0.001703617"/>
|
||||||
|
<xacro:property name="trunk_ixz" value="0.000235941"/>
|
||||||
|
<xacro:property name="trunk_iyy" value="0.24693924"/>
|
||||||
|
<xacro:property name="trunk_iyz" value="0.000119783"/>
|
||||||
|
<xacro:property name="trunk_izz" value="0.270948307"/>
|
||||||
|
|
||||||
|
<!-- hip (left front) -->
|
||||||
|
<xacro:property name="hip_mass" value="1.993"/>
|
||||||
|
<xacro:property name="hip_com_x" value="-0.022191"/>
|
||||||
|
<xacro:property name="hip_com_y" value="0.015144"/>
|
||||||
|
<xacro:property name="hip_com_z" value="-0.000015"/>
|
||||||
|
<xacro:property name="hip_ixx" value="0.002446735"/>
|
||||||
|
<xacro:property name="hip_ixy" value="-0.00059805"/>
|
||||||
|
<xacro:property name="hip_ixz" value="0.000001945"/>
|
||||||
|
<xacro:property name="hip_iyy" value="0.003925876"/>
|
||||||
|
<xacro:property name="hip_iyz" value="0.000001284"/>
|
||||||
|
<xacro:property name="hip_izz" value="0.004148145"/>
|
||||||
|
|
||||||
|
<xacro:property name="hip_rotor_mass" value="0.146"/>
|
||||||
|
<xacro:property name="hip_rotor_com_x" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_com_y" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_com_z" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_ixx" value="0.000138702"/>
|
||||||
|
<xacro:property name="hip_rotor_ixy" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_ixz" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_iyy" value="0.000083352"/>
|
||||||
|
<xacro:property name="hip_rotor_iyz" value="0.0"/>
|
||||||
|
<xacro:property name="hip_rotor_izz" value="0.000083352"/>
|
||||||
|
|
||||||
|
<!-- thigh -->
|
||||||
|
<xacro:property name="thigh_mass" value="0.639"/>
|
||||||
|
<xacro:property name="thigh_com_x" value="-0.005607"/>
|
||||||
|
<xacro:property name="thigh_com_y" value="-0.003877"/>
|
||||||
|
<xacro:property name="thigh_com_z" value="-0.048199"/>
|
||||||
|
<xacro:property name="thigh_ixx" value="0.004173855"/>
|
||||||
|
<xacro:property name="thigh_ixy" value="0.000010284"/>
|
||||||
|
<xacro:property name="thigh_ixz" value="-0.000318874"/>
|
||||||
|
<xacro:property name="thigh_iyy" value="0.004343802"/>
|
||||||
|
<xacro:property name="thigh_iyz" value="0.000109233"/>
|
||||||
|
<xacro:property name="thigh_izz" value="0.000340136"/>
|
||||||
|
|
||||||
|
<xacro:property name="thigh_rotor_mass" value="0.146"/>
|
||||||
|
<xacro:property name="thigh_rotor_com_x" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_com_y" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_com_z" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_ixx" value="0.000083352"/>
|
||||||
|
<xacro:property name="thigh_rotor_ixy" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_ixz" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_iyy" value="0.000138702"/>
|
||||||
|
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
|
||||||
|
<xacro:property name="thigh_rotor_izz" value="0.000083352"/>
|
||||||
|
|
||||||
|
<!-- calf -->
|
||||||
|
<xacro:property name="calf_mass" value="0.207"/>
|
||||||
|
<xacro:property name="calf_com_x" value="0.002781"/>
|
||||||
|
<xacro:property name="calf_com_y" value="0.000063"/>
|
||||||
|
<xacro:property name="calf_com_z" value="-0.142518"/>
|
||||||
|
<xacro:property name="calf_ixx" value="0.002129279"/>
|
||||||
|
<xacro:property name="calf_ixy" value="0.000000039"/>
|
||||||
|
<xacro:property name="calf_ixz" value="0.000005757"/>
|
||||||
|
<xacro:property name="calf_iyy" value="0.002141463"/>
|
||||||
|
<xacro:property name="calf_iyz" value="-0.000000516"/>
|
||||||
|
<xacro:property name="calf_izz" value="0.000037583"/>
|
||||||
|
|
||||||
|
<xacro:property name="calf_rotor_mass" value="0.132"/>
|
||||||
|
<xacro:property name="calf_rotor_com_x" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_com_y" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_com_z" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_ixx" value="0.000145463"/>
|
||||||
|
<xacro:property name="calf_rotor_ixy" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_ixz" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_iyy" value="0.000133031"/>
|
||||||
|
<xacro:property name="calf_rotor_iyz" value="0.0"/>
|
||||||
|
<xacro:property name="calf_rotor_izz" value="0.000145463"/>
|
||||||
|
|
||||||
|
<!-- foot -->
|
||||||
|
<xacro:property name="foot_mass" value="0.06"/>
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,266 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot>
|
||||||
|
<!-- ros_control plugin -->
|
||||||
|
<gazebo>
|
||||||
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||||
|
<robotNamespace>/aliengo_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>
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,275 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:include filename="$(find aliengo_description)/xacro/transmission.xacro"/>
|
||||||
|
|
||||||
|
<xacro:macro name="leg" params="name mirror mirror_dae front_hind front_hind_dae">
|
||||||
|
|
||||||
|
<joint name="${name}_hip_joint" type="revolute">
|
||||||
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${leg_offset_x} ${-leg_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${leg_offset_x} ${leg_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${-leg_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${-leg_offset_x} ${leg_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<parent link="trunk"/>
|
||||||
|
<child link="${name}_hip"/>
|
||||||
|
<axis xyz="1 0 0"/>
|
||||||
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
|
<xacro:if value="${(mirror_dae == True)}">
|
||||||
|
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${hip_position_min}"
|
||||||
|
upper="${hip_position_max}"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == False)}">
|
||||||
|
<limit effort="${hip_torque_max}" velocity="${hip_velocity_max}" lower="${-hip_position_max}"
|
||||||
|
upper="${-hip_position_min}"/>
|
||||||
|
</xacro:if>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="${name}_hip_rotor_joint" type="fixed">
|
||||||
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||||
|
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<parent link="trunk"/>
|
||||||
|
<child link="${name}_hip_rotor"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="${name}_hip">
|
||||||
|
<visual>
|
||||||
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||||
|
<origin rpy="${PI} 0 0" xyz="0 0 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||||
|
<origin rpy="0 ${PI} 0" xyz="0 0 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||||
|
<origin rpy="${PI} ${PI} 0" xyz="0 0 0"/>
|
||||||
|
</xacro:if>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="file://$(find aliengo_description)/meshes/hip.dae" scale="1 1 1"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="orange"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="${PI/2.0} 0 0" xyz="0 ${hip_offset*mirror} 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="${hip_length}" radius="${hip_radius}"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="${hip_com_x*front_hind} ${hip_com_y*mirror} ${hip_com_z}"/>
|
||||||
|
<mass value="${hip_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${hip_ixx}" ixy="${hip_ixy*mirror*front_hind}" ixz="${hip_ixz*front_hind}"
|
||||||
|
iyy="${hip_iyy}" iyz="${hip_iyz*mirror}"
|
||||||
|
izz="${hip_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="${name}_hip_rotor">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="green"/>
|
||||||
|
</visual>
|
||||||
|
<!-- <collision>
|
||||||
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
|
</geometry>
|
||||||
|
</collision> -->
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="${hip_rotor_com_x} ${hip_rotor_com_y} ${hip_rotor_com_z}"/>
|
||||||
|
<mass value="${hip_rotor_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${hip_rotor_ixx}" ixy="${hip_rotor_ixy}" ixz="${hip_rotor_ixz}"
|
||||||
|
iyy="${hip_rotor_iyy}" iyz="${hip_rotor_iyz}"
|
||||||
|
izz="${hip_rotor_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="${name}_thigh_joint" type="continuous">
|
||||||
|
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||||
|
<parent link="${name}_hip"/>
|
||||||
|
<child link="${name}_thigh"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
|
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="${name}_thigh_rotor_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="${thigh_rotor_offset_x} ${thigh_rotor_offset_y*mirror} 0"/>
|
||||||
|
<parent link="${name}_hip"/>
|
||||||
|
<child link="${name}_thigh_rotor"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="${name}_thigh">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<xacro:if value="${mirror_dae == True}">
|
||||||
|
<mesh filename="file://$(find aliengo_description)/meshes/thigh.dae" scale="1 1 1"/>
|
||||||
|
</xacro:if>
|
||||||
|
<xacro:if value="${mirror_dae == False}">
|
||||||
|
<mesh filename="file://$(find aliengo_description)/meshes/thigh_mirror.dae" scale="1 1 1"/>
|
||||||
|
</xacro:if>
|
||||||
|
</geometry>
|
||||||
|
<material name="orange"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-thigh_length/2.0}"/>
|
||||||
|
<geometry>
|
||||||
|
<box size="${thigh_length} ${thigh_width} ${thigh_height}"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="${thigh_com_x} ${thigh_com_y*mirror} ${thigh_com_z}"/>
|
||||||
|
<mass value="${thigh_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${thigh_ixx}" ixy="${thigh_ixy*mirror}" ixz="${thigh_ixz}"
|
||||||
|
iyy="${thigh_iyy}" iyz="${thigh_iyz*mirror}"
|
||||||
|
izz="${thigh_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="${name}_thigh_rotor">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="green"/>
|
||||||
|
</visual>
|
||||||
|
<!-- <collision>
|
||||||
|
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
|
</geometry>
|
||||||
|
</collision> -->
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="${thigh_rotor_com_x} ${thigh_rotor_com_y} ${thigh_rotor_com_z}"/>
|
||||||
|
<mass value="${thigh_rotor_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${thigh_rotor_ixx}" ixy="${thigh_rotor_ixy}" ixz="${thigh_rotor_ixz}"
|
||||||
|
iyy="${thigh_rotor_iyy}" iyz="${thigh_rotor_iyz}"
|
||||||
|
izz="${thigh_rotor_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="${name}_calf_joint" type="revolute">
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||||
|
<parent link="${name}_thigh"/>
|
||||||
|
<child link="${name}_calf"/>
|
||||||
|
<axis xyz="0 1 0"/>
|
||||||
|
<dynamics damping="${damping}" friction="${friction}"/>
|
||||||
|
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}"
|
||||||
|
upper="${calf_position_max}"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="${name}_calf_rotor_joint" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="${calf_rotor_offset_x} ${calf_rotor_offset_y*mirror} 0"/>
|
||||||
|
<parent link="${name}_thigh"/>
|
||||||
|
<child link="${name}_calf_rotor"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="${name}_calf">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="file://$(find aliengo_description)/meshes/calf.dae" scale="1 1 1"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="orange"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 ${-calf_length/2.0}"/>
|
||||||
|
<geometry>
|
||||||
|
<box size="${calf_length} ${calf_width} ${calf_height}"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="${calf_com_x} ${calf_com_y} ${calf_com_z}"/>
|
||||||
|
<mass value="${calf_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${calf_ixx}" ixy="${calf_ixy}" ixz="${calf_ixz}"
|
||||||
|
iyy="${calf_iyy}" iyz="${calf_iyz}"
|
||||||
|
izz="${calf_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<link name="${name}_calf_rotor">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="green"/>
|
||||||
|
</visual>
|
||||||
|
<!-- <collision>
|
||||||
|
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<cylinder length="0.02" radius="0.035"/>
|
||||||
|
</geometry>
|
||||||
|
</collision> -->
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="${calf_rotor_com_x} ${calf_rotor_com_y} ${calf_rotor_com_z}"/>
|
||||||
|
<mass value="${calf_rotor_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${calf_rotor_ixx}" ixy="${calf_rotor_ixy}" ixz="${calf_rotor_ixz}"
|
||||||
|
iyy="${calf_rotor_iyy}" iyz="${calf_rotor_iyz}"
|
||||||
|
izz="${calf_rotor_izz}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<joint name="${name}_foot_fixed" type="fixed">
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||||
|
<parent link="${name}_calf"/>
|
||||||
|
<child link="${name}_foot"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<link name="${name}_foot">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="${foot_radius-0.01}"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="green"/>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="${foot_radius}"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<inertial>
|
||||||
|
<mass value="${foot_mass}"/>
|
||||||
|
<inertia
|
||||||
|
ixx="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" ixy="0.0" ixz="0.0"
|
||||||
|
iyy="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}" iyz="0.0"
|
||||||
|
izz="${(2*foot_mass)/5.0*(foot_radius*foot_radius)}"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<xacro:leg_transmission name="${name}"/>
|
||||||
|
</xacro:macro>
|
||||||
|
</robot>
|
|
@ -0,0 +1,40 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot>
|
||||||
|
|
||||||
|
<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 1.0"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="silver">
|
||||||
|
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="orange">
|
||||||
|
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<material name="brown">
|
||||||
|
<color rgba="${222/255} ${207/255} ${195/255} 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>
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,105 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
|
<robot name="aliengo" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:arg name="DEBUG" default="false"/>
|
||||||
|
|
||||||
|
<xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/>
|
||||||
|
<xacro:include filename="$(find aliengo_description)/xacro/materials.xacro"/>
|
||||||
|
<xacro:include filename="$(find aliengo_description)/xacro/leg.xacro"/>
|
||||||
|
<xacro:include filename="$(find aliengo_description)/xacro/ros2_control.xacro"/>
|
||||||
|
<!-- <xacro:include filename="$(find aliengo_description)/xacro/gazebo.xacro"/>-->
|
||||||
|
|
||||||
|
<!-- 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"/>
|
||||||
|
</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="file://$(find 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>
|
||||||
|
<!-- <collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="package://aliengo_description/meshes/trunk.dae" scale="1 1 1"/>
|
||||||
|
</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>
|
||||||
|
|
||||||
|
<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"/>
|
||||||
|
|
||||||
|
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
|
||||||
|
|
||||||
|
</robot>
|
|
@ -0,0 +1,176 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<ros2_control name="UnitreeSystem" type="system">
|
||||||
|
|
||||||
|
<hardware>
|
||||||
|
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
|
||||||
|
</hardware>
|
||||||
|
|
||||||
|
<joint name="FR_hip_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="FR_thigh_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="FR_calf_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="FL_hip_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="FL_thigh_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="FL_calf_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="RR_hip_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="RR_thigh_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="RR_calf_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="RL_hip_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="RL_thigh_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="RL_calf_joint">
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<command_interface name="effort"/>
|
||||||
|
<command_interface name="kp"/>
|
||||||
|
<command_interface name="kd"/>
|
||||||
|
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
<state_interface name="effort"/>
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<sensor name="imu_sensor">
|
||||||
|
<state_interface name="orientation.w"/>
|
||||||
|
<state_interface name="orientation.x"/>
|
||||||
|
<state_interface name="orientation.y"/>
|
||||||
|
<state_interface name="orientation.z"/>
|
||||||
|
<state_interface name="angular_velocity.x"/>
|
||||||
|
<state_interface name="angular_velocity.y"/>
|
||||||
|
<state_interface name="angular_velocity.z"/>
|
||||||
|
<state_interface name="linear_acceleration.x"/>
|
||||||
|
<state_interface name="linear_acceleration.y"/>
|
||||||
|
<state_interface name="linear_acceleration.z"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
<sensor name="foot_force">
|
||||||
|
<state_interface name="FR"/>
|
||||||
|
<state_interface name="FL"/>
|
||||||
|
<state_interface name="RR"/>
|
||||||
|
<state_interface name="RL"/>
|
||||||
|
</sensor>
|
||||||
|
|
||||||
|
</ros2_control>
|
||||||
|
|
||||||
|
</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>
|
|
@ -0,0 +1,42 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:macro name="leg_transmission" params="name">
|
||||||
|
|
||||||
|
<transmission name="${name}_hip_tran">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="${name}_hip_joint">
|
||||||
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="${name}_hip_motor">
|
||||||
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="${name}_thigh_tran">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="${name}_thigh_joint">
|
||||||
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="${name}_thigh_motor">
|
||||||
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
<transmission name="${name}_calf_tran">
|
||||||
|
<type>transmission_interface/SimpleTransmission</type>
|
||||||
|
<joint name="${name}_calf_joint">
|
||||||
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
|
</joint>
|
||||||
|
<actuator name="${name}_calf_motor">
|
||||||
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||||
|
<mechanicalReduction>1</mechanicalReduction>
|
||||||
|
</actuator>
|
||||||
|
</transmission>
|
||||||
|
|
||||||
|
</xacro:macro>
|
||||||
|
|
||||||
|
</robot>
|
Loading…
Reference in New Issue