-
Notifications
You must be signed in to change notification settings - Fork 23
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #2 from IntelligentRoboticsLabs/humble-devel
1.0.0
- Loading branch information
Showing
81 changed files
with
2,753 additions
and
143 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -20,7 +20,7 @@ jobs: | |
- name: Build ROS 2 package | ||
uses: ros-tooling/[email protected] | ||
with: | ||
package-name: go2_robot go2_description go2_interfaces | ||
package-name: go2_robot go2_description go2_bringup go2_driver go2_hardware go2_simulation unitree_api unitree_go go2_interfaces go2_nav go2_rviz | ||
target-ros2-distro: humble | ||
colcon-defaults: | | ||
{ | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -12,6 +12,9 @@ jobs: | |
- name: Checkout | ||
uses: actions/checkout@v2 | ||
|
||
- name: Install nlohmann | ||
run: sudo apt -y install nlohmann-json3-dev | ||
|
||
- name: Setup ROS 2 environment | ||
uses: ros-tooling/[email protected] | ||
with: | ||
|
@@ -20,7 +23,7 @@ jobs: | |
- name: Build ROS 2 package | ||
uses: ros-tooling/[email protected] | ||
with: | ||
package-name: go2_robot go2_description go2_interfaces | ||
package-name: go2_robot go2_description go2_bringup go2_driver go2_hardware go2_simulation unitree_api unitree_go go2_interfaces go2_nav go2_rviz | ||
target-ros2-distro: humble | ||
colcon-defaults: | | ||
{ | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1 +1,218 @@ | ||
# Unitree GO2 Robot | ||
# Unitree GO2 Robot ROS 2 | ||
|
||
<p align="center"> | ||
<img width="1280" height="420" src="https://github.com/IntelligentRoboticsLabs/go2_robot/assets/44479765/da616d77-cf4d-4acf-af2f-adc99f4f72d7)" alt='Go2 point cloud'> | ||
</p> | ||
|
||
[![License](https://img.shields.io/badge/license-BSD--3-yellow.svg)](https://opensource.org/licenses/BSD-3-Clause) | ||
![distro](https://img.shields.io/badge/Ubuntu%2022-Jammy%20Jellyfish-green) | ||
![distro](https://img.shields.io/badge/ROS2-Humble-blue) | ||
[![humble](https://github.com/IntelligentRoboticsLabs/go2_robot/actions/workflows/humble.yaml/badge.svg)](https://github.com/IntelligentRoboticsLabs/go2_robot/actions/workflows/humble.yaml) | ||
[![humble-devel](https://github.com/IntelligentRoboticsLabs/go2_robot/actions/workflows/humble_devel.yaml/badge.svg)](https://github.com/IntelligentRoboticsLabs/go2_robot/actions/workflows/humble_devel.yaml) | ||
|
||
In this package is our integration for the Unitee Go2 robot. | ||
|
||
## Checklist | ||
|
||
- [x] robot description | ||
- [x] odom | ||
- [x] pointcloud | ||
- [x] joint_states | ||
- [x] Visualization in rviz | ||
- [x] cmd_vel | ||
- [x] go2_interfaces | ||
- [x] Change modes | ||
- [x] Change configuration for robot | ||
- [ ] SLAM (working in progress) | ||
- [ ] Nav2 (working in progress) | ||
- [ ] Ros2cli | ||
- [ ] Hardware interface | ||
- [ ] Gazebo simulation | ||
|
||
## Installation | ||
You need to have previously installed ROS2. Please follow this [guide](https://docs.ros.org/en/humble/Installation.html) if you don't have it. | ||
|
||
```bash | ||
source /opt/ros/humble/setup.bash | ||
``` | ||
|
||
Create workspace and clone the repository | ||
|
||
```bash | ||
mkdir ~/go2_ws/src | ||
cd ~/go2_ws/src | ||
git clone https://github.com/IntelligentRoboticsLabs/go2_robot.git -b humble | ||
``` | ||
|
||
Install dependencies and build workspace | ||
```bash | ||
cd ~/go2_ws | ||
sudo rosdep init | ||
rosdep update | ||
rosdep install --from-paths src --ignore-src -r -y | ||
colcon build --symlink-install | ||
``` | ||
|
||
Setup the workspace | ||
```bash | ||
source ~/ros2_ws/install/setup.bash | ||
``` | ||
|
||
## Sensor installation | ||
If you have purchased a hesai lidar 3d, or a realsense d435i, follow the following steps inside the robot. | ||
|
||
### Hesai Lidar | ||
|
||
```bash | ||
sudo apt-get install libboost-all-dev | ||
sudo apt-get install -y libyaml-cpp-dev | ||
git clone --recurse-submodules https://github.com/HesaiTechnology/HesaiLidar_ROS_2.0.git | ||
cd .. | ||
source /opt/ros/$ROS_DISTRO/setup.bash | ||
rosdep install --from-paths src --ignore-src -r -y | ||
colcon build --symlink-install | ||
source install/setup.bash | ||
``` | ||
|
||
Set the lidar IP to `config/config.yaml` | ||
```yaml | ||
lidar: | ||
- driver: | ||
udp_port: 2368 #UDP port of lidar | ||
ptc_port: 9347 #PTC port of lidar | ||
device_ip_address: <Device IP> #IP address of lidar | ||
pcap_path: "<Your PCAP file path>" #The path of pcap file (set during offline playback) | ||
correction_file_path: "<Your correction file path>" #LiDAR angle file, required for offline playback of pcap/packet rosbag | ||
firetimes_path: "<Your firetime file path>" #The path of firetimes file | ||
source_type: 2 #The type of data source, 1: real-time lidar connection, 2: pcap, 3: packet rosbag | ||
pcap_play_synchronization: true #Pcap play rate synchronize with the host time | ||
x: 0 #Calibration parameter | ||
y: 0 #Calibration parameter | ||
z: 0 #Calibration parameter | ||
roll: 0 #Calibration parameter | ||
pitch: 0 #Calibration parameter | ||
yaw: 0 #Calibration parameter | ||
ros: | ||
ros_frame_id: hesai_lidar #Frame id of packet message and point cloud message | ||
ros_recv_packet_topic: /lidar_packets #Topic used to receive lidar packets from ROS | ||
ros_send_packet_topic: /lidar_packets #Topic used to send lidar packets through ROS | ||
ros_send_point_cloud_topic: /lidar_points #Topic used to send point cloud through ROS | ||
send_packet_ros: true #true: Send packets through ROS | ||
send_point_cloud_ros: true #true: Send point cloud through ROS | ||
``` | ||
### Realsense d435i | ||
```bash | ||
sudo apt install ros-humble-realsense2-camera | ||
``` | ||
|
||
## Usage | ||
### Bringup the robot | ||
Either from your computer, or from inside the robot, execute the following: | ||
```bash | ||
ros2 launch go2_bringup go2.launch.py | ||
``` | ||
> If you have a realsense and a lidar inside the robot, use the lidar or realsense parameters. | ||
> It will only work if you throw everything inside the robot | ||
If you want to see your robot through rviz, do it as follows: | ||
```bash | ||
ros2 launch go2_bringup go2.launch.py rviz:=True | ||
``` | ||
|
||
### Change modes | ||
If what you want is for your robot to be able to change modes, thus performing the movements predefined by the controller, use the following service: | ||
```bash | ||
ros2 service call /mode go2_interfaces/srv/Mode "mode: 'hello'" | ||
``` | ||
|
||
<details> | ||
<summary>Available modes</summary> | ||
``` | ||
damp | ||
balance_stand | ||
stop_move | ||
stand_up | ||
stand_down | ||
sit | ||
rise_sit | ||
hello | ||
stretch | ||
wallow | ||
scrape | ||
front_flip | ||
front_jump | ||
front_pounce | ||
dance1 | ||
dance2 | ||
finger_heart | ||
``` | ||
</details> | ||
|
||
### Change configurations for robot | ||
If you want, you can modify the ways the robot walks, the height of the base, the height of the legs when walking... I show you the different parameters that can be modified: | ||
|
||
- BodyHeight: Set the relative height of the body above the ground when standing and walking. [0.3 ~ 0.5] | ||
```bash | ||
ros2 service call /body_height go2_interfaces/srv/BodyHeight "height: 0.0" | ||
``` | ||
- ContinuousGait: Continuous movement | ||
```bash | ||
ros2 service call /continuous_gait go2_interfaces/srv/ContinuousGait "flag: false" | ||
``` | ||
- Euler: Posture when standing and walking. [-0.75 ~ 0.75] [-0.75 ~ 0.75] [-1.5 ~ 1.5] | ||
```bash | ||
ros2 service call /euler go2_interfaces/srv/Euler "roll: 0.0 pitch: 0.0 yaw: 0.0" | ||
``` | ||
- FootRaiseHeight: Set the relative height of foot lift during movement [-0.06 ~ 0.03] | ||
```bash | ||
ros2 service call /foot_raise_height go2_interfaces/srv/FootRaiseHeight "height: 0.0" | ||
``` | ||
- Pose: Set true to pose and false to restore | ||
```bash | ||
ros2 service call /pose go2_interfaces/srv/Pose "flag: false" | ||
``` | ||
- SpeedLevel: Set the speed range [-1 ~ 1] | ||
```bash | ||
ros2 service call /speed_level go2_interfaces/srv/SpeedLevel "level: 0" | ||
``` | ||
- SwitchGait: Switch gait [0 - 4] | ||
```bash | ||
ros2 service call /switch_gait go2_interfaces/srv/SwitchGait "d: 0" | ||
``` | ||
- SwitchJoystick: Native remote control response switch | ||
```bash | ||
ros2 service call /switch_joystick go2_interfaces/srv/SwitchJoystick "flag: false" | ||
``` | ||
|
||
## SLAM | ||
In the future, work in progress. | ||
|
||
## NAVIGATION | ||
In the future, work in progress. | ||
|
||
## Demos | ||
### Robot description | ||
|
||
[go2_tf.webm](https://github.com/IntelligentRoboticsLabs/go2_robot/assets/44479765/b019e6fc-875f-4870-a510-afa6e1353e08) | ||
|
||
### Robot PointCloud | ||
|
||
https://github.com/IntelligentRoboticsLabs/go2_robot/assets/44479765/c164840a-6857-4d95-a50e-023c5bb44edb | ||
|
||
## Acknowledgment | ||
Thanks to [unitree](https://github.com/unitreerobotics/unitree_ros2) for providing the support and communication interfaces with the robot. | ||
|
||
## About | ||
This is a project made by the [Intelligent Robotics Lab](https://intelligentroboticslab.gsyc.urjc.es/), a research group from the [Universidad Rey Juan Carlos](https://www.urjc.es/). | ||
Copyright © 2024. | ||
|
||
Maintainers: | ||
|
||
* [Juan Carlos Manzanares Serrano](https://github.com/Juancams) | ||
* [Juan S. Cely](https://github.com/juanscelyg) | ||
|
||
## License | ||
|
||
This project is licensed under the BSD 3-clause License - see the [LICENSE](https://github.com/IntelligentRoboticsLabs/go2_robot/blob/humble/LICENSE) file for details. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,22 @@ | ||
cmake_minimum_required(VERSION 3.8) | ||
project(go2_bringup) | ||
|
||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
add_compile_options(-Wall -Wextra -Wpedantic) | ||
endif() | ||
|
||
find_package(ament_cmake REQUIRED) | ||
|
||
install(DIRECTORY | ||
launch | ||
DESTINATION share/${PROJECT_NAME} | ||
) | ||
|
||
if(BUILD_TESTING) | ||
find_package(ament_lint_auto REQUIRED) | ||
set(ament_cmake_copyright_FOUND TRUE) | ||
set(ament_cmake_cpplint_FOUND TRUE) | ||
ament_lint_auto_find_test_dependencies() | ||
endif() | ||
|
||
ament_package() |
Empty file.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,107 @@ | ||
# BSD 3-Clause License | ||
|
||
# Copyright (c) 2024, Intelligent Robotics Lab | ||
# All rights reserved. | ||
|
||
# Redistribution and use in source and binary forms, with or without | ||
# modification, are permitted provided that the following conditions are met: | ||
|
||
# * Redistributions of source code must retain the above copyright notice, this | ||
# list of conditions and the following disclaimer. | ||
|
||
# * Redistributions in binary form must reproduce the above copyright notice, | ||
# this list of conditions and the following disclaimer in the documentation | ||
# and/or other materials provided with the distribution. | ||
|
||
# * Neither the name of the copyright holder nor the names of its | ||
# contributors may be used to endorse or promote products derived from | ||
# this software without specific prior written permission. | ||
|
||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE | ||
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE | ||
# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL | ||
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR | ||
# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER | ||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, | ||
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE | ||
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. | ||
|
||
import os | ||
|
||
from ament_index_python.packages import get_package_share_directory | ||
from launch import LaunchDescription | ||
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription | ||
from launch.conditions import IfCondition | ||
from launch.launch_description_sources import PythonLaunchDescriptionSource | ||
from launch.substitutions import LaunchConfiguration, PythonExpression | ||
|
||
|
||
def generate_launch_description(): | ||
lidar = LaunchConfiguration('lidar') | ||
realsense = LaunchConfiguration('realsense') | ||
rviz = LaunchConfiguration('rviz') | ||
|
||
declare_lidar_cmd = DeclareLaunchArgument( | ||
'lidar', | ||
default_value='False', | ||
description='Launch hesai lidar driver' | ||
) | ||
|
||
declare_realsense_cmd = DeclareLaunchArgument( | ||
'realsense', | ||
default_value='False', | ||
description='Launch realsense driver' | ||
) | ||
|
||
declare_rviz_cmd = DeclareLaunchArgument( | ||
'rviz', | ||
default_value='False', | ||
description='Launch rviz' | ||
) | ||
|
||
robot_description_cmd = IncludeLaunchDescription( | ||
PythonLaunchDescriptionSource([os.path.join( | ||
get_package_share_directory('go2_description'), | ||
'launch/'), 'robot.launch.py']) | ||
) | ||
|
||
driver_cmd = IncludeLaunchDescription( | ||
PythonLaunchDescriptionSource([os.path.join( | ||
get_package_share_directory('go2_driver'), | ||
'launch/'), 'go2_driver.launch.py']) | ||
) | ||
|
||
lidar_cmd = IncludeLaunchDescription( | ||
PythonLaunchDescriptionSource([os.path.join( | ||
get_package_share_directory('hesai_ros_driver'), | ||
'launch/'), 'start.py']), | ||
condition=IfCondition(PythonExpression([lidar])) | ||
) | ||
|
||
realsense_cmd = IncludeLaunchDescription( | ||
PythonLaunchDescriptionSource([os.path.join( | ||
get_package_share_directory('realsense2_camera'), | ||
'launch/'), 'rs_launch.py']), | ||
condition=IfCondition(PythonExpression([realsense])) | ||
) | ||
|
||
rviz_cmd = IncludeLaunchDescription( | ||
PythonLaunchDescriptionSource([os.path.join( | ||
get_package_share_directory('go2_rviz'), | ||
'launch/'), 'rviz.launch.py']), | ||
condition=IfCondition(PythonExpression([rviz])) | ||
) | ||
|
||
ld = LaunchDescription() | ||
ld.add_action(declare_lidar_cmd) | ||
ld.add_action(declare_realsense_cmd) | ||
ld.add_action(declare_rviz_cmd) | ||
ld.add_action(robot_description_cmd) | ||
ld.add_action(lidar_cmd) | ||
ld.add_action(realsense_cmd) | ||
ld.add_action(driver_cmd) | ||
ld.add_action(rviz_cmd) | ||
|
||
return ld |
Oops, something went wrong.