Skip to content

Commit

Permalink
Merge pull request #8 from Space-Robotics-Laboratory/release/v3.0
Browse files Browse the repository at this point in the history
Release/v3.0
  • Loading branch information
ribeirowarley authored Aug 27, 2021
2 parents c44c188 + b66e58e commit 4721d9f
Show file tree
Hide file tree
Showing 199 changed files with 9,572 additions and 2,716 deletions.
33 changes: 25 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# ClimbLab - Climbing robot Matlab simulator

![ex3_uneven_dynamic_Uno-gait-planning_stability_polyhedron.gif](./docs/media/ex3_uneven_dynamic_Uno-gait-planning_stability_polyhedron.gif)
![climblab.png](./docs/media/climblab.png)

Author(s) and maintainer(s): [Space Robotics Lab.](http://www.astro.mech.tohoku.ac.jp/e/index.html) Climbing Robotics Team

Expand All @@ -27,9 +27,20 @@ This simulator wraps up functions for:
|--------|--------|
| 3) Stability region visualization [2] | 4) Topographically salient region detection and non-periodic foothold selection [3] |

## Usage
## Publication

If you use this simulator in academic context, please put citations of the following publications.
If you use this simulator in an academic context, please cite the following publication.
> K. Uno, W. F. R. Ribeiro, Y. Koizumi, K. Haji, K. Kurihara, W. Jones, and K. Yoshida
> **"ClimbLab: MATLAB Simulation Platform for Legged Climbing Robotics"**,
> Proceedings of the 24th International Conference on Climbing and Walking Robots and the Support Technologies for Mobile Machines (CLAWAR), 2021.
@inproceedings{uno2021climblab,
title={ClimbLab: MATLAB Simulation Platform for Legged Climbing Robotics},
author={Kentaro Uno and Warley F. R. Ribeiro and Yusuke Koizumi and Keigo Haji and Koki Kurihara and William Jones and Kazuya Yoshida},
booktitle={Proceedings of the 24th International Conference on Climbing and Walking Robots and the Support Technologies for Mobile Machines (CLAWAR)},
pages={TBD},
year={2021}
}

#### Requirements
We confirmed the code is working with:
Expand All @@ -46,7 +57,9 @@ We confirmed the code is working with:
- Note: If you select USER configuration type, follow instructions described in the `config/USER/config_USER_param_template.m`.
* Run `src/climb_main.m` file (**Note: MATLAB might ask you to change folder or add path. Choose to "add path"**)

## Publications
## References

Our recent works using ClimbLab simulator are as follows:

[1] Kentaro Uno *et al*., "[Gait Planning for a Free-Climbing Robot Based on Tumble Stability](https://ieeexplore.ieee.org/document/8700455)", Proceedings of the 2019 IEEE/SICE International Symposium on System Integration (SII), Paris, France, 2019, pp. 289-294, [doi: 10.1109/SII.2019.8700455](https://doi.org/10.1109/SII.2019.8700455).

Expand All @@ -58,12 +71,16 @@ We confirmed the code is working with:

Please contact us by sending an email to the following address if there is any question or suggestion.

limb[at]astro.mech.tohoku.ac.jp
srl-limb[at]grp.tohoku.ac.jp

## Release note

* Version 1.0: released on 18th Sept. 2020.
* Version 2.0: released on 26th Oct. 2020. This version includes:
- topographically salient regioon detection algorithm [3]
- non-periodic gait plannner [3]
- gripper detachment evaluation
- topographically salient region detection algorithm [3]
- non-periodic gait planner [3]
- gripper detachment evaluation
* Version 3.0: released on 27th Aug.2021. This version includes
- Camera sensing
- New robot models
- More analysis scripts
21 changes: 15 additions & 6 deletions config/USER/config_USER_param_template.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
%%%%%%
%%%%%% Created 2020-07-08
%%%%%% Warley Ribeiro
%%%%%% Last update: 2020-10-01
%%%%%% Last update: 2021-07-26
%%%%%% Keigo Haji
%
%
Expand All @@ -18,7 +18,7 @@
% OUTPUT
% robot_param
% environment_param
% gait_param
% gait_planning_param
% control_param
% equilibrium_eval_param
% ani_settings
Expand All @@ -27,12 +27,13 @@
% gripper_param
% map_param
% matching_settings
% sensing_camera_param
% INPUT
% -

function [robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings] = config_USER_param(robot_param, environment_param, gait_param, control_param, ...
equilibrium_eval_param, ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings)
function [robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_USER_param(robot_param, environment_param, gait_planning_param, control_param, ...
equilibrium_eval_param, ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param)
%% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Robot Parameters %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%


Expand All @@ -44,7 +45,12 @@


%% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Control Parameters %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

if contains(robot_param.robot_type, 'HubRobo_v3')
%%% Controller Proportional (P) gain
control_param.kp = 10.0;
%%% Controller Derivative (D) gain
control_param.kd = 0.3;
end

%% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Equilibrium Parameters %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

Expand All @@ -67,4 +73,7 @@
%% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Matching Settings %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%


%% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Sensing Camera Parameters %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%


end
51 changes: 51 additions & 0 deletions config/config_all_default_param.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
%%%%%% Configuration
%%%%%% config_all_default_param
%%%%%%
%%%%%% Define all default parameters
%%%%%%
%%%%%% Created 2021-03-02
%%%%%% Keigo Haji
%%%%%% Last update: 2021-04-24
%%%%%% Kentaro Uno
%
%
% Define and load configurations for all default parameters.
%
% Function variables:
%
% OUTPUT
% robot_param
% environment_param
% gait_planning_param
% control_param
% equilibrium_eval_param
% ani_settings
% save_settings
% plot_settings
% gripper_param
% map_param
% matching_settings
% sensing_camera_param
% INPUT
% -
%
%
function [robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_all_default_param()


% Load all default parameters
robot_param = config_robot_param();
environment_param = config_environment_param();
gait_planning_param = config_gait_planning_param();
control_param = config_control_param();
equilibrium_eval_param = config_equilibrium_param();
ani_settings = config_animation_settings();
save_settings = config_save_settings(environment_param);
plot_settings = config_plot_settings();
[gripper_param, map_param, matching_settings] = config_target_detection_param();
sensing_camera_param = config_sensing_camera_param();


end

44 changes: 0 additions & 44 deletions config/config_gait_param.m

This file was deleted.

28 changes: 0 additions & 28 deletions config/config_save_settings.m

This file was deleted.

93 changes: 64 additions & 29 deletions config/config_simulation.m
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
%%%%%%
%%%%%% Created 2020-07-09
%%%%%% Warley Ribeiro
%%%%%% Last update: 2020-10-15
%%%%%% Keentaro Uno
%%%%%% Last update: 2021-07-08
%%%%%% Keigo Haji
%
%
% Load configurations for simulation
Expand All @@ -16,7 +16,7 @@
% OUTPUT
% robot_param
% environment_param
% gait_param
% gait_planning_param
% control_param
% equilibrium_eval_param
% ani_settings
Expand All @@ -25,48 +25,83 @@
% gripper_param
% map_param
% matching_settings
% sensing_camera_param
% INPUT
% config

function [robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings] = config_simulation(config)
function [robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_simulation(config)
%% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% General settings %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

robot_param = config_robot_param();
environment_param = config_environment_param();
gait_param = config_gait_param();
control_param = config_control_param();
equilibrium_eval_param = config_equilibrium_param();
% Load all default parameters
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_all_default_param();

ani_settings = config_animation_settings();
save_settings = config_save_settings();
plot_settings = config_plot_settings();
[gripper_param, map_param, matching_settings] = config_target_detection_param();

% Reads the config file with the specified config name and overwrites the variables
if strcmp(config,'USER')
[robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings] = config_USER_param(robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings);
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_USER_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param);
end
if strcmp(config,'example_demo_1')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_example_demo_1_param(robot_param, environment_param, gait_planning_param, control_param, ...
equilibrium_eval_param, ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param);
end
if strcmp(config,'example_demo_2')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_example_demo_2_param(robot_param, environment_param, gait_planning_param, control_param, ...
equilibrium_eval_param, ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param);
end
if strcmp(config,'example_demo_3')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_example_demo_3_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param);
end
if strcmp(config,'gia_static')
[robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_gia_static(robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ...
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_gia_static_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings);
end
if strcmp(config,'uno_crawl_param')
[robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_uno_crawl_param(robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ...
if strcmp(config,'clawar_2021_dynamic_climbing_demo')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_clawar_2021_dynamic_climbing_demo_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings);
end
if strcmp(config,'nonperiodic_demo_param')
[robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_nonperiodic_demo_param(robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ...
if strcmp(config,'crawl_gait_for_discrete_footholds')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_crawl_gait_for_discrete_footholds_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings);
end
if strcmp(config,'iSAIRAS_2020_demo_param')
[robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings] = config_iSAIRAS_2020_demo_param(robot_param, environment_param, gait_param, control_param, equilibrium_eval_param, ...
if strcmp(config,'nonperiodic_gait_for_discrete_footholds')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_nonperiodic_gait_for_discrete_footholds_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings);
end
if strcmp(config,'iSAIRAS_2020_demo')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_iSAIRAS_2020_demo_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param);
end
if strcmp(config,'base_pos_opt_quasistatic')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings] = config_base_pos_opt_quasistatic_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings);
end

if strcmp(config,'clawar_2021_dynamic_climbing_demo')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_clawar_2021_dynamic_climbing_demo_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings);
end
if strcmp(config,'clawar_2021_statistical_analysis')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings] = config_clawar_2021_statistical_analysis_param(robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ...
ani_settings, save_settings, plot_settings);
end
if strcmp(config,'hubrobo_testfield_exp')
[robot_param, environment_param, gait_planning_param, control_param, equilibrium_eval_param, ani_settings, save_settings, ...
plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param] = config_hubrobo_testfield_exp_param(robot_param, environment_param, gait_planning_param, control_param, ...
equilibrium_eval_param, ani_settings, save_settings, plot_settings, gripper_param, map_param, matching_settings, sensing_camera_param);
end
end
Loading

0 comments on commit 4721d9f

Please sign in to comment.