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

Update chassis compensation #183

Closed
wants to merge 4 commits into from

Conversation

321Aurora
Copy link

No description provided.

gen.add("k_chassis_vel_", double_t, 0, "Yaw chassis velocity feedforward scale", 0.0, 0, 1.0)
gen.add("a_compensation",double_t, 0,"A param of chassis_compensation", 0.0, 0, 999.0)
gen.add("b_compensation",double_t, 0,"A param of chassis_compensation", 0.0, 0, 999.0)
gen.add("c_compensation",double_t, 0,"A param of chassis_compensation", 0.0, 0, 999.0)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

变量的名字不对,修改一下

@@ -60,7 +60,7 @@ namespace rm_gimbal_controllers
{
struct GimbalConfig
{
double yaw_k_v_, pitch_k_v_, k_chassis_vel_;
double yaw_k_v_, pitch_k_v_, a_compensation, b_compensation, c_compensation;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

变量的名字格式不对

@@ -148,6 +148,8 @@ class Controller : public controller_interface::MultiInterfaceController<rm_cont
void moveJoint(const ros::Time& time, const ros::Duration& period);
double feedForward(const ros::Time& time);
void updateChassisVel();
double chassis_compensation;
double updateCompensation(double chassis_vel_angular_z);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

变量怎么和函数放一起了

.k_chassis_vel_ = getParam(controller_nh, "yaw/k_chassis_vel", 0.),
.a_compensation = getParam(controller_nh,"yaw/a_compensation",0.),
.b_compensation = getParam(controller_nh,"yaw/b_compensation",0.),
.c_compensation = getParam(controller_nh,"yaw/c_compensation",0.),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

变量格式

@@ -173,7 +175,7 @@ void Controller::update(const ros::Time& time, const ros::Duration& period)
}
catch (tf2::TransformException& ex)
{
ROS_WARN_THROTTLE(1, "%s\n", ex.what());
ROS_WARN("%s", ex.what());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

这个不要修改主分支,ROS_WARN_THROTTLE(1, "%s\n", ex.what());

Copy link
Contributor

@YoujianWu YoujianWu left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

先把我评论的问题都解决了

@321Aurora 321Aurora closed this Nov 17, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants