add visualizer

This commit is contained in:
Huang Zhenbiao 2024-09-30 20:02:56 +08:00
parent e6778af705
commit 44df86fc7f
19 changed files with 675 additions and 107 deletions

BIN
.images/aliengo.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 34 KiB

BIN
.images/b2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 53 KiB

BIN
.images/go1.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

BIN
.images/go2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 53 KiB

View File

@ -7,21 +7,38 @@ This repository contains the ros2-control based controllers for the quadruped ro
* [Hardwares](hardwares): contains the ros2-control hardware interface for the robot
Todo List:
- [x] Mujoco Simulation
- [x] Unitree Guide Controller
- [x] Gazebo Simulation
- [x] Leg PD Controller
- [x] Contact Sensor
- [x] OCS2 Legged Control
- [x] [Mujoco Simulation](hardwares/hardware_unitree_mujoco)
- [x] [Unitree Guide Controller](controllers/unitree_guide_controller)
- [x] [Gazebo Simulation](descriptions/quadruped_gazebo)
- [x] [Leg PD Controller](controllers/leg_pd_controller)
- [x] [Contact Sensor Simulation](https://github.com/legubiao/unitree_mujoco)
- [x] [OCS2 Quadruped Control](controllers/ocs2_quadruped_controller)
- [ ] Learning-based Controller
Video for Unitree Guide Controller:
[![](http://i1.hdslb.com/bfs/archive/310e6208920985ac43015b2da31c01ec15e2c5f9.jpg)](https://www.bilibili.com/video/BV1aJbAeZEuo/)
## 1. Build
## Quick Start
* rosdep
```bash
cd ~/ros2_ws
rosdep install --from-paths src --ignore-src -r -y
```
```
* Compile the package
```bash
colcon build --packages-up-to unitree_guide_controller go2_description keyboard_input hardware_unitree_mujoco
```
* Launch the unitree mujoco go2 simulation
* Launch the ros2-control
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch go2_description unitree_guide.launch.py
```
* Run the keyboard control node
```bash
source ~/ros2_ws/install/setup.bash
ros2 run keyboard_input keyboard_input
```
For more details, please refer to the [unitree guide controller](controllers/unitree_guide_controller/) and [go2 description](descriptions/go2_description/).

View File

@ -80,6 +80,12 @@ install(
RUNTIME DESTINATION bin
)
install(
DIRECTORY config
DESTINATION share/${PROJECT_NAME}/
)
ament_export_dependencies(${CONTROLLER_INCLUDE_DEPENDS})
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)

View File

@ -36,3 +36,8 @@ colcon build --packages-up-to ocs2_quadruped_controller
source ~/ros2_ws/install/setup.bash
ros2 launch go2_description ocs2_control.launch.py
```
* Unitree B2 Robot
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch b2_description ocs2_control.launch.py
```

View File

@ -0,0 +1,607 @@
Panels:
- Class: rviz_common/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded:
- /TF1/Frames1
- /Optimized State Trajectory1
- /Target Trajectories1/Target Feet Trajectories1/Marker1
- /Target Trajectories1/Target Feet Trajectories1/Marker2
- /Target Trajectories1/Target Feet Trajectories1/Marker3
- /Target Trajectories1/Target Feet Trajectories1/Marker4
- /Target Trajectories1/Target Base Trajectory1
Splitter Ratio: 0.5
Tree Height: 477
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Pose Estimate1
- /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: ""
- Class: rviz_common/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.8294117450714111
Tree Height: 301
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: odom
Value: true
- Alpha: 0.4000000059604645
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
head_Link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lidar_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
tail_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
trunk:
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
- Class: rviz_default_plugins/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: false
FL_calf:
Value: true
FL_calf_rotor:
Value: true
FL_foot:
Value: true
FL_hip:
Value: true
FL_hip_rotor:
Value: true
FL_thigh:
Value: true
FL_thigh_rotor:
Value: true
FR_calf:
Value: true
FR_calf_rotor:
Value: true
FR_foot:
Value: true
FR_hip:
Value: true
FR_hip_rotor:
Value: true
FR_thigh:
Value: true
FR_thigh_rotor:
Value: true
RL_calf:
Value: true
RL_calf_rotor:
Value: true
RL_foot:
Value: true
RL_hip:
Value: true
RL_hip_rotor:
Value: true
RL_thigh:
Value: true
RL_thigh_rotor:
Value: true
RR_calf:
Value: true
RR_calf_rotor:
Value: true
RR_foot:
Value: true
RR_hip:
Value: true
RR_hip_rotor:
Value: true
RR_thigh:
Value: true
RR_thigh_rotor:
Value: true
base:
Value: false
head_Link:
Value: true
imu_link:
Value: false
lidar_link:
Value: true
odom:
Value: false
tail_link:
Value: true
trunk:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: false
Show Names: false
Tree:
odom:
base:
trunk:
FL_hip:
FL_thigh:
FL_calf:
FL_foot:
{}
FL_calf_rotor:
{}
FL_thigh_rotor:
{}
FL_hip_rotor:
{}
FR_hip:
FR_thigh:
FR_calf:
FR_foot:
{}
FR_calf_rotor:
{}
FR_thigh_rotor:
{}
FR_hip_rotor:
{}
RL_hip:
RL_thigh:
RL_calf:
RL_foot:
{}
RL_calf_rotor:
{}
RL_thigh_rotor:
{}
RL_hip_rotor:
{}
RR_hip:
RR_thigh:
RR_calf:
RR_foot:
{}
RR_calf_rotor:
{}
RR_thigh_rotor:
{}
RR_hip_rotor:
{}
head_Link:
{}
imu_link:
{}
lidar_link:
{}
tail_link:
{}
Update Interval: 0
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
Name: Optimized State Trajectory
Namespaces:
CoM Trajectory: true
EE Trajectories: true
Future footholds: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/optimizedStateTrajectory
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
Name: Current State
Namespaces:
Center of Pressure: true
EE Forces: true
EE Positions: true
Support Polygon: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/currentState
Value: true
- Class: rviz_common/Group
Displays:
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/LF
Value: true
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/LH
Value: true
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/RF
Value: true
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Marker
Namespaces:
{}
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredFeetTrajectory/RH
Value: true
Enabled: false
Name: Target Feet Trajectories
- Class: rviz_default_plugins/Marker
Enabled: true
Name: Target Base Trajectory
Namespaces:
"": true
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /legged_robot/desiredBaseTrajectory
Value: true
Enabled: true
Name: Target Trajectories
- Alpha: 1
Autocompute Intensity Bounds: true
Class: grid_map_rviz_plugin/GridMap
Color: 200; 200; 200
Color Layer: elevation
Color Transformer: GridMapLayer
Enabled: true
Height Layer: elevation
Height Transformer: GridMapLayer
History Length: 1
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 10
Min Color: 0; 0; 0
Min Intensity: 0
Name: GridMap
Show Grid Lines: true
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /raisim_heightmap
Use Rainbow: true
Value: true
Enabled: true
Global Options:
Background Color: 238; 238; 238
Fixed Frame: odom
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/Select
- 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: /move_base_simple/goal
- 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: 4.046566963195801
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.5368534326553345
Y: 0.8848452568054199
Z: 0.04236998409032822
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.4303978383541107
Target Frame: <Fixed Frame>
Value: Orbit (rviz_default_plugins)
Yaw: 5.236791610717773
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 655
Hide Left Dock: true
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000032c000002a7fc020000000afb0000001200530065006c0065006300740069006f006e000000006e000000b00000005d00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000006e000004770000005d00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003f000002a7000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000fb000000100044006900730070006c006100790073000000006e00000247000000cc00ffffff000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d00650000000000000006400000026f00fffffffb0000000800540069006d00650100000000000004500000000000000000000004000000023100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1024
X: 828
Y: 212

View File

@ -10,6 +10,7 @@
#include <hardware_interface/loaned_state_interface.hpp>
#include <control_input_msgs/msg/inputs.hpp>
#include <ocs2_mpc/SystemObservation.h>
#include <ocs2_legged_robot_ros/visualization/LeggedRobotVisualizer.h>
#include "TargetManager.h"
#include "ocs2_quadruped_controller/estimator/StateEstimateBase.h"
@ -46,6 +47,7 @@ struct CtrlComponent {
std::shared_ptr<ocs2::legged_robot::StateEstimateBase> estimator_;
std::shared_ptr<ocs2::legged_robot::TargetManager> target_manager_;
std::shared_ptr<ocs2::legged_robot::LeggedRobotVisualizer> visualizer_;
CtrlComponent() {
}

View File

@ -109,6 +109,10 @@ namespace ocs2::legged_robot {
ctrl_comp_.joint_kd_command_interface_[i].get().set_value(default_kd_);
}
// Visualization
ctrl_comp_.visualizer_->update(ctrl_comp_.observation_, mpc_mrt_interface_->getPolicy(),
mpc_mrt_interface_->getCommand());
observation_publisher_->publish(ros_msg_conversions::createObservationMsg(ctrl_comp_.observation_));
return controller_interface::return_type::OK;
@ -150,8 +154,11 @@ namespace ocs2::legged_robot {
eeKinematicsPtr_ = std::make_shared<PinocchioEndEffectorKinematics>(
legged_interface_->getPinocchioInterface(), pinocchio_mapping,
legged_interface_->modelSettings().contactNames3DoF);
// robotVisualizer_ = std::make_shared<LeggedRobotVisualizer>(leggedInterface_->getPinocchioInterface(),
// leggedInterface_->getCentroidalModelInfo(), *eeKinematicsPtr_, nh);
ctrl_comp_.visualizer_ = std::make_shared<LeggedRobotVisualizer>(
legged_interface_->getPinocchioInterface(), legged_interface_->getCentroidalModelInfo(), *eeKinematicsPtr_,
get_node());
// selfCollisionVisualization_.reset(new LeggedSelfCollisionVisualization(leggedInterface_->getPinocchioInterface(),
// leggedInterface_->getGeometryInterface(), pinocchioMapping, nh));

View File

@ -1,6 +1,8 @@
# Unitree AlienGo Description
This repository contains the urdf model of Aliengo.
![Aliengo](../../.images/aliengo.png)
Tested environment:
* Ubuntu 24.04
* ROS2 Jazzy

View File

@ -11,7 +11,7 @@ from launch_ros.substitutions import FindPackageShare
from sympy.physics.vector.printing import params
package_description = "aliengo_description"
package_controller = "ocs2_quadruped_controller"
def process_xacro(context):
robot_type_value = context.launch_configurations['robot_type']
@ -107,7 +107,7 @@ def generate_launch_description():
description='Type of the robot'
)
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.rviz")
return LaunchDescription([
robot_type_arg,

View File

@ -276,12 +276,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -294,7 +288,7 @@
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.278" velocity="20"/>
<limit effort="35.278" lower="-2.0943951023931953" upper="4.1887902047863905" velocity="20"/>
</joint>
<joint name="FR_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 -0.0298 0"/>
@ -329,12 +323,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -360,7 +348,6 @@
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -380,14 +367,7 @@
<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="0.0 0.0 0.0"/>
<mass value="0.132"/>
@ -405,7 +385,6 @@
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -489,12 +468,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -507,7 +480,7 @@
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.278" velocity="20"/>
<limit effort="35.278" lower="-2.0943951023931953" upper="4.1887902047863905" velocity="20"/>
</joint>
<joint name="FL_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.0298 0"/>
@ -542,12 +515,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -573,7 +540,6 @@
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -593,14 +559,7 @@
<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="0.0 0.0 0.0"/>
<mass value="0.132"/>
@ -618,7 +577,6 @@
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -702,12 +660,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -720,7 +672,7 @@
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.278" velocity="20"/>
<limit effort="35.278" lower="-2.0943951023931953" upper="4.1887902047863905" velocity="20"/>
</joint>
<joint name="RR_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 -0.0298 0"/>
@ -755,12 +707,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -786,7 +732,6 @@
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -806,14 +751,7 @@
<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="0.0 0.0 0.0"/>
<mass value="0.132"/>
@ -831,7 +769,6 @@
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -915,12 +852,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -933,7 +864,7 @@
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.278" velocity="20"/>
<limit effort="35.278" lower="-2.0943951023931953" upper="4.1887902047863905" velocity="20"/>
</joint>
<joint name="RL_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.0298 0"/>
@ -968,12 +899,6 @@
</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="0.0 0.0 0.0"/>
<mass value="0.146"/>
@ -999,7 +924,6 @@
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/aliengo_description/share/aliengo_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.125"/>
@ -1019,14 +943,7 @@
<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="0.0 0.0 0.0"/>
<mass value="0.132"/>
@ -1044,7 +961,6 @@
<geometry>
<sphere radius="0.0165"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>

View File

@ -109,7 +109,8 @@
<child link="${name}_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="${damping}" friction="${friction}"/>
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}"/>
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}"
upper="${thigh_position_max}"/>
</joint>
<joint name="${name}_thigh_rotor_joint" type="fixed">

View File

@ -1,6 +1,7 @@
# Unitree B2 Description
This repository contains the urdf model of b2.
![B2](../../.images/b2.png)
## Build
```bash

View File

@ -19,7 +19,7 @@ swing_trajectory_config
{
liftOffVelocity 0.5
touchDownVelocity -1.0
swingHeight 0.3
swingHeight 0.25
swingTimeScale 0.30
}

View File

@ -11,7 +11,7 @@ from launch_ros.substitutions import FindPackageShare
from sympy.physics.vector.printing import params
package_description = "b2_description"
package_controller = "ocs2_quadruped_controller"
def process_xacro(context):
robot_type_value = context.launch_configurations['robot_type']
@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs):
"--controller-manager", "/controller_manager"],
)
unitree_guide_controller = Node(
ocs2_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
@ -94,7 +94,7 @@ def launch_setup(context, *args, **kwargs):
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=imu_sensor_broadcaster,
on_exit=[unitree_guide_controller],
on_exit=[ocs2_controller],
)
),
]
@ -103,11 +103,11 @@ def launch_setup(context, *args, **kwargs):
def generate_launch_description():
robot_type_arg = DeclareLaunchArgument(
'robot_type',
default_value='go2',
default_value='aliengo',
description='Type of the robot'
)
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.rviz")
return LaunchDescription([
robot_type_arg,

View File

@ -1,6 +1,8 @@
# Unitree Go1 Description
This repository contains the urdf model of go1.
![go1](../../.images/go1.png)
## Build
```bash
cd ~/ros2_ws

View File

@ -1,6 +1,8 @@
# Unitree Go2 Description
This repository contains the urdf model of go2.
![go2](../../.images/go2.png)
Tested environment:
* Ubuntu 24.04
* ROS2 Jazzy