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

[Feature] Adjust locomotion function for dynamic kick #28

Open
wants to merge 25 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
399b881
feat: adjust positioning function to dynamic kick
Mobilizes May 16, 2024
dc8a226
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri May 21, 2024
4f6810d
feat: differ tilt range for dynamic kick
hiikariri May 29, 2024
7d3e161
Merge branch 'feature/inverse-a-move-pivot' of github.com:ichiro-its/…
Mobilizes Jun 3, 2024
154f2c7
fix: fix tilt range
Mobilizes Jun 8, 2024
303cd15
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 8, 2024
76e3356
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 10, 2024
50cd023
fix: normalize target direction
hiikariri Jun 12, 2024
9565364
fix: use one algo of inverse a move
hiikariri Jun 12, 2024
2f74e3f
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 14, 2024
dbbf0b6
fix: add time filter of positioning to prevent jumping tilt value
hiikariri Jun 14, 2024
57485e0
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 14, 2024
2a5ec12
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 15, 2024
03613ef
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 19, 2024
75e2c52
Merge branch 'feature/adjust-function-for-dynamic-kick' of github.com…
hiikariri Jun 19, 2024
26871ee
feat: refactor positioning, remove time usage
hiikariri Jun 19, 2024
bef5814
Merge branch 'hotfix/fix-positioning-target-head' of github.com:ichir…
hiikariri Jun 23, 2024
7410719
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 25, 2024
572b531
feat: add dynamic range config
hiikariri Jun 26, 2024
48aa9d9
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 26, 2024
2bfb923
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jun 27, 2024
d2ff8e6
refactor: return to previous style
hiikariri Jun 30, 2024
e8a41f6
Delete wrong wget-log
hiikariri Jun 30, 2024
4ab3c42
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jul 1, 2024
96607e3
Merge branch 'master' of github.com:ichiro-its/suiryoku into feature/…
hiikariri Jul 7, 2024
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
9 changes: 7 additions & 2 deletions include/suiryoku/locomotion/process/locomotion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class Locomotion
const keisan::Angle<double> & max_pan, const keisan::Angle<double> & min_tilt,
const keisan::Angle<double> & max_tilt);
bool position_kick_general(const keisan::Angle<double> & direction);
bool position_kick_range_pan_tilt(const keisan::Angle<double> & direction, bool precise_kick, bool left_kick, bool is_positioning_center);
bool position_kick_range_pan_tilt(const keisan::Angle<double> & direction, bool precise_kick, bool left_kick, bool dynamic_kick, bool is_positioning_center);

bool is_time_to_follow();
bool pivot_fulfilled();
Expand All @@ -90,7 +90,6 @@ class Locomotion
keisan::Angle<double> pivot_stop_limit;

private:

double move_min_x;
double move_max_x;
double move_max_y;
Expand Down Expand Up @@ -168,6 +167,12 @@ class Locomotion
keisan::Angle<double> right_kick_target_tilt;

std::shared_ptr<Robot> robot;

keisan::Angle<double> max_dynamic_range_pan;
keisan::Angle<double> min_dynamic_range_pan;
keisan::Angle<double> max_dynamic_range_tilt;
keisan::Angle<double> min_dynamic_range_tilt;
double mapped_tilt;
};

} // namespace suiryoku
Expand Down
39 changes: 35 additions & 4 deletions src/suiryoku/locomotion/process/locomotion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,10 @@ void Locomotion::set_config(const nlohmann::json & json)
double position_max_range_pan_double;
double position_center_right_range_pan_double;
double position_center_left_range_pan_double;
double min_dynamic_range_pan_double;
double max_dynamic_range_pan_double;
double min_dynamic_range_tilt_double;
double max_dynamic_range_tilt_double;

valid_section &= jitsuyo::assign_val(position_section, "min_x", position_min_x);
valid_section &= jitsuyo::assign_val(position_section, "max_x", position_max_x);
Expand All @@ -226,6 +230,11 @@ void Locomotion::set_config(const nlohmann::json & json)
valid_section &= jitsuyo::assign_val(position_section, "center_right_range_pan", position_center_right_range_pan_double);
valid_section &= jitsuyo::assign_val(position_section, "center_left_range_pan", position_center_left_range_pan_double);

valid_section &= jitsuyo::assign_val(position_section, "min_dynamic_range_pan", min_dynamic_range_pan_double);
valid_section &= jitsuyo::assign_val(position_section, "max_dynamic_range_pan", max_dynamic_range_pan_double);
valid_section &= jitsuyo::assign_val(position_section, "min_dynamic_range_tilt", min_dynamic_range_tilt_double);
valid_section &= jitsuyo::assign_val(position_section, "max_dynamic_range_tilt", max_dynamic_range_tilt_double);

position_min_delta_tilt = keisan::make_degree(position_min_delta_tilt_double);
position_min_delta_pan = keisan::make_degree(position_min_delta_pan_double);
position_min_delta_pan_tilt = keisan::make_degree(position_min_delta_pan_tilt_double);
Expand All @@ -236,6 +245,10 @@ void Locomotion::set_config(const nlohmann::json & json)
position_max_range_pan = keisan::make_degree(position_max_range_pan_double);
position_center_right_range_pan = keisan::make_degree(position_center_right_range_pan_double);
position_center_left_range_pan = keisan::make_degree(position_center_left_range_pan_double);
min_dynamic_range_pan = keisan::make_degree(min_dynamic_range_pan_double);
max_dynamic_range_pan = keisan::make_degree(max_dynamic_range_pan_double);
min_dynamic_range_tilt = keisan::make_degree(min_dynamic_range_tilt_double);
max_dynamic_range_tilt = keisan::make_degree(max_dynamic_range_tilt_double);

if (!valid_section) {
std::cout << "Error found at section `position`" << std::endl;
Expand Down Expand Up @@ -890,13 +903,31 @@ bool Locomotion::position_kick_custom_pan_tilt(const keisan::Angle<double> & dir
return false;
}

bool Locomotion::position_kick_range_pan_tilt(const keisan::Angle<double> & direction, bool precise_kick, bool left_kick, bool is_positioning_center)
bool Locomotion::position_kick_range_pan_tilt(const keisan::Angle<double> & direction, bool precise_kick, bool left_kick, bool dynamic_kick, bool is_positioning_center)
{
if (dynamic_kick) {
position_max_range_pan = max_dynamic_range_pan;
position_min_range_pan = min_dynamic_range_pan;
position_min_range_tilt = min_dynamic_range_tilt;
position_max_range_tilt = max_dynamic_range_tilt;
}

auto tilt = robot->get_tilt();
auto pan = robot->get_pan();
auto delta_direction = (direction - robot->orientation).normalize().degree();

bool tilt_in_range = tilt > position_min_range_tilt && tilt < position_max_range_tilt;
if (dynamic_kick && pan < keisan::make_degree(0.0))
mapped_tilt = keisan::exponentialmap(pan.degree(), 0.0, position_min_range_pan.degree(), position_min_range_tilt.degree(), position_max_range_tilt.degree());
else if (dynamic_kick && pan >= keisan::make_degree(0.0))
mapped_tilt = keisan::exponentialmap(pan.degree(), 0.0, position_max_range_pan.degree(), position_min_range_tilt.degree(), position_max_range_tilt.degree());
printf("mapped tilt: %.2f\n", mapped_tilt);

keisan::Angle<double> min_tilt = (dynamic_kick) ? keisan::make_degree(mapped_tilt) - position_min_delta_tilt : position_min_range_tilt;
keisan::Angle<double> max_tilt = (dynamic_kick) ? keisan::make_degree(mapped_tilt) + position_min_delta_tilt : position_max_range_tilt;
printf("tilt range: %.2f to %.2f\n", min_tilt.degree(), max_tilt.degree());
printf("pan range: %.2f to %.2f\n", position_min_range_pan.degree(), position_max_range_pan.degree());

bool tilt_in_range = tilt > min_tilt && tilt < max_tilt;
bool right_kick_in_range = pan > position_min_range_pan && pan < -position_center_right_range_pan;
bool left_kick_in_range = pan > position_center_left_range_pan && pan < position_max_range_pan;
bool pan_in_range = precise_kick ? (left_kick ? left_kick_in_range : right_kick_in_range) : (right_kick_in_range || left_kick_in_range);
Expand All @@ -906,7 +937,7 @@ bool Locomotion::position_kick_range_pan_tilt(const keisan::Angle<double> & dire
return true;
}

// y movement
// y movement
if (!precise_kick) left_kick = pan > 0.0_deg;
auto target_pan = left_kick ? left_kick_target_pan : right_kick_target_pan;

Expand All @@ -916,7 +947,7 @@ bool Locomotion::position_kick_range_pan_tilt(const keisan::Angle<double> & dire

double delta_pan = (target_pan - pan).degree();
double y_speed = 0.0;

if (!pan_in_range) {
if (delta_pan < -position_min_delta_pan.degree()) {
y_speed = keisan::map(delta_pan, -20.0, -position_min_delta_pan.degree(), position_max_ly, position_min_ly);
Expand Down
Loading