Skip to content

Commit

Permalink
Remove unused variables and log statement
Browse files Browse the repository at this point in the history
  • Loading branch information
Ar-Ray-code committed Mar 12, 2024
1 parent fc51781 commit 57da21a
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 14 deletions.
12 changes: 0 additions & 12 deletions auto_driver_interface/src/tf_to_position_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,14 +99,6 @@ namespace auto_driver_interface
auto z = transform2.transform.translation.z - transform.transform.translation.z;
auto current_rotation = transform.transform.rotation;

double yaw_gap, pitch_gap, current_roll, yaw_gap_deg, pitch_gap_deg;
tf2::Quaternion q(current_rotation.x, current_rotation.y, current_rotation.z, current_rotation.w);
tf2::Matrix3x3 m(q);
m.getRPY(current_roll, pitch_gap, yaw_gap);
auto roll_gap_deg = current_roll * 180 / M_PI;
yaw_gap_deg = yaw_gap * 180 / M_PI;
pitch_gap_deg = pitch_gap * 180 / M_PI;

auto yaw = atan2(y, x);
yaw = (x < 0) ? -yaw : yaw;
auto degree = yaw * 180 / M_PI;
Expand All @@ -118,12 +110,8 @@ namespace auto_driver_interface

result->yaw_deg = static_cast<int32_t>(degree);
result->pitch_deg = static_cast<int32_t>(pitch);
result->yaw_gap_deg = static_cast<int32_t>(yaw_gap_deg);
result->pitch_gap_deg = static_cast<int32_t>(pitch_gap_deg);
result->succeed = true;

RCLCPP_INFO(this->get_logger(), "yaw: %f", degree);

goal_handle->succeed(result);
return;
}
Expand Down
2 changes: 0 additions & 2 deletions auto_driver_msgs/action/GetAnglesFromTf.action
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,5 @@ string target_tf_frame_id
bool succeed
int32 yaw_deg
int32 pitch_deg
int32 yaw_gap_deg
int32 pitch_gap_deg
---
#feedback definition

0 comments on commit 57da21a

Please sign in to comment.