Skip to content

Commit

Permalink
Fix code specification.
Browse files Browse the repository at this point in the history
  • Loading branch information
321Aurora committed Nov 23, 2024
1 parent fb462ec commit 8899129
Showing 1 changed file with 7 additions and 5 deletions.
12 changes: 7 additions & 5 deletions rm_gimbal_controllers/src/gimbal_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro

config_ = { .yaw_k_v_ = getParam(nh_yaw, "k_v", 0.),
.pitch_k_v_ = getParam(nh_pitch, "k_v", 0.),
.chassis_comp_a_ = getParam(controller_nh,"yaw/chassis_comp_a",0.),
.chassis_comp_b_ = getParam(controller_nh,"yaw/chassis_comp_b",0.),
.chassis_comp_c_ = getParam(controller_nh,"yaw/chassis_comp_c",0.),
.chassis_comp_a_ = getParam(controller_nh, "yaw/chassis_comp_a", 0.),
.chassis_comp_b_ = getParam(controller_nh, "yaw/chassis_comp_b", 0.),
.chassis_comp_c_ = getParam(controller_nh, "yaw/chassis_comp_c", 0.),
.accel_pitch_ = getParam(controller_nh, "pitch/accel", 99.),
.accel_yaw_ = getParam(controller_nh, "yaw/accel", 99.) };
config_rt_buffer_.initRT(config_);
Expand Down Expand Up @@ -502,7 +502,8 @@ void Controller::moveJoint(const ros::Time& time, const ros::Duration& period)
}
loop_count_++;

ctrl_yaw_.setCommand(pid_yaw_pos_.getCurrentCmd() - updateCompensation(chassis_vel_->angular_->z()) * chassis_vel_->angular_->z() +
ctrl_yaw_.setCommand(pid_yaw_pos_.getCurrentCmd() -
updateCompensation(chassis_vel_->angular_->z()) * chassis_vel_->angular_->z() +
config_.yaw_k_v_ * yaw_vel_des + ctrl_yaw_.joint_.getVelocity() - angular_vel_yaw.z);
ctrl_pitch_.setCommand(pid_pitch_pos_.getCurrentCmd() + config_.pitch_k_v_ * pitch_vel_des +
ctrl_pitch_.joint_.getVelocity() - angular_vel_pitch.y);
Expand Down Expand Up @@ -552,7 +553,8 @@ void Controller::updateChassisVel()

double Controller::updateCompensation(double chassis_vel_angular_z)
{
chassis_compensation_ = config_.chassis_comp_a_ * pow(chassis_vel_angular_z,2) + config_.chassis_comp_b_ * chassis_vel_angular_z + config_.chassis_comp_c_;
chassis_compensation_ = config_.chassis_comp_a_ * pow(chassis_vel_angular_z, 2) +
config_.chassis_comp_b_ * chassis_vel_angular_z + config_.chassis_comp_c_;
return chassis_compensation_;
}

Expand Down

0 comments on commit 8899129

Please sign in to comment.