Skip to content

Commit

Permalink
Merge pull request #23 from ichiro-its/hotfix/remove-inverse-a-move
Browse files Browse the repository at this point in the history
[Hotfix] - Remove Inverse A Move
  • Loading branch information
FaaizHaikal authored Jun 15, 2024
2 parents 8d39225 + e5f5c70 commit 1cbd350
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 7 deletions.
1 change: 0 additions & 1 deletion include/suiryoku/locomotion/model/robot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,6 @@ class Robot
double y_speed;
double a_speed;
bool aim_on;
bool inverse_a_move;
};

} // namespace suiryoku
Expand Down
2 changes: 1 addition & 1 deletion include/suiryoku/locomotion/process/locomotion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class Locomotion

bool dribble(const keisan::Angle<double> & direction);
bool pivot(const keisan::Angle<double> & direction);
bool pivot_inverse_a_move(const keisan::Angle<double> & direction);
bool pivot_new(const keisan::Angle<double> & direction);

bool position_until(
const keisan::Angle<double> & target_pan,
Expand Down
1 change: 0 additions & 1 deletion src/suiryoku/locomotion/node/locomotion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
7 changes: 3 additions & 4 deletions src/suiryoku/locomotion/process/locomotion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -615,7 +615,7 @@ bool Locomotion::pivot(const keisan::Angle<double> & direction)
return false;
}

bool Locomotion::pivot_inverse_a_move(const keisan::Angle<double> & direction)
bool Locomotion::pivot_new(const keisan::Angle<double> & direction)
{
if (initial_pivot) {
initial_pivot = false;
Expand All @@ -627,13 +627,12 @@ bool Locomotion::pivot_inverse_a_move(const keisan::Angle<double> & 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);

Expand Down Expand Up @@ -662,7 +661,7 @@ bool Locomotion::pivot_inverse_a_move(const keisan::Angle<double> & 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;
Expand Down

0 comments on commit 1cbd350

Please sign in to comment.