From e5f5c7038f85a421cae1e951d08cb64097c29748 Mon Sep 17 00:00:00 2001 From: FaaizHaikal Date: Sat, 15 Jun 2024 16:35:25 +0700 Subject: [PATCH] fix: remove inverse a move --- include/suiryoku/locomotion/model/robot.hpp | 1 - include/suiryoku/locomotion/process/locomotion.hpp | 2 +- src/suiryoku/locomotion/node/locomotion_node.cpp | 1 - src/suiryoku/locomotion/process/locomotion.cpp | 7 +++---- 4 files changed, 4 insertions(+), 7 deletions(-) diff --git a/include/suiryoku/locomotion/model/robot.hpp b/include/suiryoku/locomotion/model/robot.hpp index 4b62520..86c4517 100644 --- a/include/suiryoku/locomotion/model/robot.hpp +++ b/include/suiryoku/locomotion/model/robot.hpp @@ -57,7 +57,6 @@ class Robot double y_speed; double a_speed; bool aim_on; - bool inverse_a_move; }; } // namespace suiryoku diff --git a/include/suiryoku/locomotion/process/locomotion.hpp b/include/suiryoku/locomotion/process/locomotion.hpp index b46c24f..b7eecd9 100755 --- a/include/suiryoku/locomotion/process/locomotion.hpp +++ b/include/suiryoku/locomotion/process/locomotion.hpp @@ -59,7 +59,7 @@ class Locomotion bool dribble(const keisan::Angle & direction); bool pivot(const keisan::Angle & direction); - bool pivot_inverse_a_move(const keisan::Angle & direction); + bool pivot_new(const keisan::Angle & direction); bool position_until( const keisan::Angle & target_pan, diff --git a/src/suiryoku/locomotion/node/locomotion_node.cpp b/src/suiryoku/locomotion/node/locomotion_node.cpp index a4e8793..ad21df9 100644 --- a/src/suiryoku/locomotion/node/locomotion_node.cpp +++ b/src/suiryoku/locomotion/node/locomotion_node.cpp @@ -95,7 +95,6 @@ void LocomotionNode::publish_walking() walking_msg.y_move = robot->y_speed; walking_msg.a_move = robot->a_speed; walking_msg.aim_on = robot->aim_on; - walking_msg.inverse_a_move = robot->inverse_a_move; set_walking_publisher->publish(walking_msg); } diff --git a/src/suiryoku/locomotion/process/locomotion.cpp b/src/suiryoku/locomotion/process/locomotion.cpp index 0ab771d..e74f40b 100755 --- a/src/suiryoku/locomotion/process/locomotion.cpp +++ b/src/suiryoku/locomotion/process/locomotion.cpp @@ -615,7 +615,7 @@ bool Locomotion::pivot(const keisan::Angle & direction) return false; } -bool Locomotion::pivot_inverse_a_move(const keisan::Angle & direction) +bool Locomotion::pivot_new(const keisan::Angle & direction) { if (initial_pivot) { initial_pivot = false; @@ -627,13 +627,12 @@ bool Locomotion::pivot_inverse_a_move(const keisan::Angle & direction) if (std::abs(delta_direction) < pivot_max_delta_direction) { walk_in_position(); - robot->inverse_a_move = false; return true; } double delta_tilt = (pivot_target_tilt - robot->tilt + robot->tilt_center).degree(); - printf("pivot inverse a move\n"); + printf("pivot new\n"); printf("delta direction %f\n", delta_direction); printf("delta tilt %f\n", delta_tilt); @@ -662,7 +661,7 @@ bool Locomotion::pivot_inverse_a_move(const keisan::Angle & direction) x_speed = keisan::smooth(robot->x_speed, x_speed, smooth_ratio); y_speed = keisan::smooth(robot->y_speed, y_speed, smooth_ratio); - robot->inverse_a_move = true; + robot->aim_on = true; robot->x_speed = x_speed; robot->y_speed = y_speed; robot->a_speed = a_speed;