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

Simplify getGimbalError(),make selected_armor to enum variable,select armor in better way #153

Merged
merged 2 commits into from
Jan 14, 2024
Merged
Changes from 1 commit
Commits
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
Next Next commit
Simplify getGimbalError().
ye-luo-xi-tui committed Jan 14, 2024
commit ade76df194223701411ee8f1aad53d57941edb40
Original file line number Diff line number Diff line change
@@ -72,8 +72,7 @@ class BulletSolver

bool solve(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double bullet_speed, double yaw, double v_yaw,
double r1, double r2, double dz, int armors_num);
double getGimbalError(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double yaw, double v_yaw, double r1,
double r2, double dz, int armors_num, double yaw_real, double pitch_real, double bullet_speed);
double getGimbalError(double yaw_real, double pitch_real);
double getResistanceCoefficient(double bullet_speed) const;
double getYaw() const
{
28 changes: 11 additions & 17 deletions rm_gimbal_controllers/src/bullet_solver.cpp
Original file line number Diff line number Diff line change
@@ -298,26 +298,17 @@ void BulletSolver::bulletModelPub(const geometry_msgs::TransformStamped& odom2pi
}
}

double BulletSolver::getGimbalError(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double yaw, double v_yaw,
double r1, double r2, double dz, int armors_num, double yaw_real, double pitch_real,
double bullet_speed)
double BulletSolver::getGimbalError(double yaw_real, double pitch_real)
{
double delay = track_target_ ? 0 : config_.delay;
double r = r1;
double z = pos.z;
if (selected_armor_ != 0)
{
r = armors_num == 4 ? r2 : r1;
z = armors_num == 4 ? pos.z + dz : pos.z;
}
double error;
if (track_target_)
{
double bullet_rho =
bullet_speed * std::cos(pitch_real) * (1 - std::exp(-resistance_coff_ * fly_time_)) / resistance_coff_;
bullet_speed_ * std::cos(pitch_real) * (1 - std::exp(-resistance_coff_ * fly_time_)) / resistance_coff_;
double bullet_x = bullet_rho * std::cos(yaw_real);
double bullet_y = bullet_rho * std::sin(yaw_real);
double bullet_z = (bullet_speed * std::sin(pitch_real) + (config_.g / resistance_coff_)) *
double bullet_z = (bullet_speed_ * std::sin(pitch_real) + (config_.g / resistance_coff_)) *
(1 - std::exp(-resistance_coff_ * fly_time_)) / resistance_coff_ -
config_.g * fly_time_ / resistance_coff_;
error = std::sqrt(std::pow(target_pos_.x - bullet_x, 2) + std::pow(target_pos_.y - bullet_y, 2) +
@@ -327,12 +318,15 @@ double BulletSolver::getGimbalError(geometry_msgs::Point pos, geometry_msgs::Vec
{
geometry_msgs::Point target_pos_after_fly_time_and_delay{};
target_pos_after_fly_time_and_delay.x =
pos.x + vel.x * (fly_time_ + delay) -
r * cos(yaw + v_yaw * (fly_time_ + delay) + selected_armor_ * 2 * M_PI / armors_num);
target_state_.current_target_center_pos.x + target_state_.current_target_center_vel.x * (fly_time_ + delay) -
target_state_.r * cos(target_state_.yaw + target_state_.v_yaw * (fly_time_ + delay) +
selected_armor_ * 2 * M_PI / target_state_.armors_num);
target_pos_after_fly_time_and_delay.y =
pos.y + vel.y * (fly_time_ + delay) -
r * sin(yaw + v_yaw * (fly_time_ + delay) + selected_armor_ * 2 * M_PI / armors_num);
target_pos_after_fly_time_and_delay.z = z + vel.z * (fly_time_ + delay);
target_state_.current_target_center_pos.y + target_state_.current_target_center_vel.y * (fly_time_ + delay) -
target_state_.r * sin(target_state_.yaw + target_state_.v_yaw * (fly_time_ + delay) +
selected_armor_ * 2 * M_PI / target_state_.armors_num);
target_pos_after_fly_time_and_delay.z =
target_state_.current_target_center_pos.z + target_state_.current_target_center_vel.z * (fly_time_ + delay);
error = std::sqrt(std::pow(target_pos_.x - target_pos_after_fly_time_and_delay.x, 2) +
std::pow(target_pos_.y - target_pos_after_fly_time_and_delay.y, 2) +
std::pow(target_pos_.z - target_pos_after_fly_time_and_delay.z, 2));
5 changes: 1 addition & 4 deletions rm_gimbal_controllers/src/gimbal_base.cpp
Original file line number Diff line number Diff line change
@@ -266,10 +266,7 @@ void Controller::track(const ros::Time& time)
{
if (error_pub_->trylock())
{
double error =
bullet_solver_->getGimbalError(target_pos, target_vel, data_track_.yaw, data_track_.v_yaw,
data_track_.radius_1, data_track_.radius_2, data_track_.dz,
data_track_.armors_num, yaw_compute, pitch_compute, cmd_gimbal_.bullet_speed);
double error = bullet_solver_->getGimbalError(yaw_compute, pitch_compute);
error_pub_->msg_.stamp = time;
error_pub_->msg_.error = solve_success ? error : 1.0;
error_pub_->unlockAndPublish();