Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding Go2 #23

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
add go2_velodyne
MarcuSpade committed Apr 19, 2024
commit 14214c10f154a4a46ae9ab6cddd57192baefc6f9
6 changes: 6 additions & 0 deletions configs/go2_velodyne_config/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(go2_velodyne_config)

find_package(catkin REQUIRED COMPONENTS)

catkin_package()
77 changes: 77 additions & 0 deletions configs/go2_velodyne_config/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@

## 1. Quick Start

You don't need a physical robot to run the following demos.

### 1.1. Walking demo in RVIZ:

#### 1.1.1. Run the base driver:

roslaunch go2_velodyne_config bringup.launch rviz:=true

#### 1.1.2. Run the teleop node:

roslaunch champ_teleop teleop.launch

If you want to use a [joystick](https://www.logitechg.com/en-hk/products/gamepads/f710-wireless-gamepad.html) add joy:=true as an argument.


### 1.2. SLAM demo:

#### 1.2.1. Run the Gazebo environment:

roslaunch go2_velodyne_config gazebo.launch

#### 1.2.2. Run gmapping package and move_base:

roslaunch go2_velodyne_config slam.launch rviz:=true

To start mapping:

- Click '2D Nav Goal'.
- Click and drag at the position you want the robot to go.

![champ](https://raw.githubusercontent.com/chvmp/champ/master/docs/images/slam.gif)

- Save the map by running:

roscd go2_velodyne_config/maps
rosrun map_server map_saver

### 1.3. Autonomous Navigation:

#### 1.3.1. Run the Gazebo environment:

roslaunch go2_velodyne_config gazebo.launch

#### 1.3.2. Run amcl and move_base:

roslaunch go2_velodyne_config navigate.launch rviz:=true

To navigate:

- Click '2D Nav Goal'.
- Click and drag at the position you want the robot to go.

![champ](https://raw.githubusercontent.com/chvmp/champ/master/docs/images/navigation.gif)

#### 1.4.1 Spawning multiple robots in Gazebo

Run Gazebo and default simulation world:

roslaunch champ_gazebo spawn_world.launch

You can also load your own world file by passing your world's path to 'gazebo_world' argument:

roslaunch champ_gazebo spawn_world.launch gazebo_world:=<path_to_world_file>

Spawning a robot:

roslaunch go2_velodyne_config spawn_robot.launch robot_name:=<unique_robot_name> world_init_x:=<x_position> world_init_y:=<y_position>


* Every instance of the spawned robot must have a unique robot name to prevent the topics and transforms from clashing.


---
:exclamation: *This is not an official product from the robot's company/author.*
211 changes: 211 additions & 0 deletions configs/go2_velodyne_config/config.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,211 @@
{
"robot_name": "go2_velodyne",
"default_urdf": "False",
"urdf_path": "$(find go2_description)/xacro/go2_velodyne_description.urdf",
"links": {
"base": "base",
"left_front": [
"FL_hip",
"FL_thigh",
"FL_calf",
"FL_foot"
],
"right_front": [
"FR_hip",
"FR_thigh",
"FR_calf",
"FR_foot"
],
"left_hind": [
"RL_hip",
"RL_thigh",
"RL_calf",
"RL_foot"
],
"right_hind": [
"RR_hip",
"RR_thigh",
"RR_calf",
"RR_foot"
]
},
"joints": {
"left_front": [
"FL_hip_joint",
"FL_thigh_joint",
"FL_calf_joint",
"FL_foot_fixed"
],
"right_front": [
"FR_hip_joint",
"FR_thigh_joint",
"FR_calf_joint",
"FR_foot_fixed"
],
"left_hind": [
"RL_hip_joint",
"RL_thigh_joint",
"RL_calf_joint",
"RL_foot_fixed"
],
"right_hind": [
"RR_hip_joint",
"RR_thigh_joint",
"RR_calf_joint",
"RR_foot_fixed"
]
},
"firmware": {
"transforms": {
"left_front": {
"hip": [
0.1934,
0.0465,
0.0,
0.0,
0.0,
0.0
],
"upper_leg": [
0.0,
0.0955,
-0.0,
0.0,
0.0,
0.0
],
"lower_leg": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
],
"foot": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
]
},
"right_front": {
"hip": [
0.1934,
-0.0465,
0.0,
0.0,
0.0,
0.0
],
"upper_leg": [
0.0,
-0.0955,
-0.0,
0.0,
0.0,
0.0
],
"lower_leg": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
],
"foot": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
]
},
"left_hind": {
"hip": [
-0.1934,
0.0465,
0.0,
0.0,
0.0,
0.0
],
"upper_leg": [
0.0,
0.0955,
-0.0,
0.0,
0.0,
0.0
],
"lower_leg": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
],
"foot": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
]
},
"right_hind": {
"hip": [
-0.1934,
-0.0465,
0.0,
0.0,
0.0,
0.0
],
"upper_leg": [
0.0,
-0.0955,
-0.0,
0.0,
0.0,
0.0
],
"lower_leg": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
],
"foot": [
0.0,
0.0,
-0.213,
0.0,
0.0,
0.0
]
}
},
"gait": {
"knee_orientation": ">>",
"odom_scaler": 1.0,
"max_linear_vel_x": 0.5,
"max_linear_vel_y": 0.25,
"max_angular_vel_z": 1.0,
"stance_duration": 0.25,
"com_x_translation": 0.0,
"swing_height": 0.04,
"stance_depth": 0.0,
"nominal_height": 0.2,
"pantograph_leg": "false"
}
}
}
11 changes: 11 additions & 0 deletions configs/go2_velodyne_config/config/gait/gait.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
knee_orientation : ">>"
pantograph_leg : false
odom_scaler: 1.0
max_linear_velocity_x : 0.5
max_linear_velocity_y : 0.25
max_angular_velocity_z : 1.0
com_x_translation : 0.0
swing_height : 0.04
stance_depth : 0.0
stance_duration : 0.25
nominal_height : 0.2
23 changes: 23 additions & 0 deletions configs/go2_velodyne_config/config/joints/joints.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
left_front:
- FL_hip_joint
- FL_thigh_joint
- FL_calf_joint
- FL_foot_fixed

right_front:
- FR_hip_joint
- FR_thigh_joint
- FR_calf_joint
- FR_foot_fixed

left_hind:
- RL_hip_joint
- RL_thigh_joint
- RL_calf_joint
- RL_foot_fixed

right_hind:
- RR_hip_joint
- RR_thigh_joint
- RR_calf_joint
- RR_foot_fixed
24 changes: 24 additions & 0 deletions configs/go2_velodyne_config/config/links/links.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
base: base
left_front:
- FL_hip
- FL_thigh
- FL_calf
- FL_foot

right_front:
- FR_hip
- FR_thigh
- FR_calf
- FR_foot

left_hind:
- RL_hip
- RL_thigh
- RL_calf
- RL_foot

right_hind:
- RR_hip
- RR_thigh
- RR_calf
- RR_foot
Loading