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

remove getHandle in UnitreeHW::read #71

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

zitongbai
Copy link

@zitongbai zitongbai commented Aug 15, 2024

I would like to express my gratitude for the wonderful framework you have shared with the community. It has been instrumental in advancing my project.

I am currently working on implementing two distinct, self-defined ROS controllers to control separate groups of joints. But this would cause resource conflict in ros control manager, the error information would be like:

[ WARN] [1723711230.086462426]: Resource conflict on [left_ankle_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086604701]: Resource conflict on [left_elbow_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086661049]: Resource conflict on [left_hip_pitch_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086710601]: Resource conflict on [left_hip_roll_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086752277]: Resource conflict on [left_hip_yaw_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086901553]: Resource conflict on [left_knee_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086953870]: Resource conflict on [left_shoulder_pitch_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.086997766]: Resource conflict on [left_shoulder_roll_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087036690]: Resource conflict on [left_shoulder_yaw_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087073432]: Resource conflict on [not_use_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087122926]: Resource conflict on [right_ankle_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087178554]: Resource conflict on [right_elbow_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087232702]: Resource conflict on [right_hip_pitch_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087275688]: Resource conflict on [right_hip_roll_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087315841]: Resource conflict on [right_hip_yaw_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087356746]: Resource conflict on [right_knee_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087425316]: Resource conflict on [right_shoulder_pitch_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087476459]: Resource conflict on [right_shoulder_roll_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087515868]: Resource conflict on [right_shoulder_yaw_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ WARN] [1723711230.087555049]: Resource conflict on [torso_joint].  Controllers = [controllers/init_joint_pos_controller, controllers/upper_joint_controller, ]
[ERROR] [1723711230.087743598]: Could not switch controllers, due to resource conflict

More details can be found in my forked version: zitongbai/bipedal_control#3

Upon further examination, I found that the calling of the getHandle("handle_name") function of HybridJointInterface would claim the "handle_name" resource, which can be referred here:

https://github.com/ros-controls/ros_control/blob/6b9fd8b3605e047ae1b925857c92998074c803c4/hardware_interface/include/hardware_interface/internal/hardware_resource_manager.h#L65-L70

And I found that the getHandle function is called in UnitreeHW::read, which causes all the joints resources are claimed each time UnitreeHW::read is invoked, no matter whether they are used in the controller:

// Set feedforward and velocity cmd to zero to avoid for safety when not controller setCommand
std::vector<std::string> names = hybridJointInterface_.getNames();
for (const auto& name : names) {
HybridJointHandle handle = hybridJointInterface_.getHandle(name);
handle.setFeedforward(0.);
handle.setVelocityDesired(0.);
handle.setKd(3.);
}

Of course, it poses no issues in the context of a single controller implementation. But it will cause some trouble when attempting to operate multiple controllers concurrently, which may be essential for further development.

Furthermore, I have yet to conduct real-world experiments to validate this behavior. It would be highly beneficial to have this aspect confirmed through practical testing :)

handle.setFeedforward(0.);
handle.setVelocityDesired(0.);
handle.setKd(3.);
for(size_t i=0; i<12; ++i){
Copy link
Owner

Choose a reason for hiding this comment

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

Should not be i<12.

jointData_[i].velDes_ = jointData_[i].vel_;
jointData_[i].ff_ = 0.0;
jointData_[i].kp_ = 0.0;
jointData_[i].kd_ = 0.0;
Copy link
Owner

Choose a reason for hiding this comment

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

Better to have some damping
jointData_[i].kd_ = 3.0;

Comment on lines +87 to +88
jointData_[i].posDes_ = jointData_[i].pos_;
jointData_[i].velDes_ = jointData_[i].vel_;
Copy link
Owner

Choose a reason for hiding this comment

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

Not need for these two lines.

@qiayuanl
Copy link
Owner

Hi, thanks for your contribution, I think you are right. I left some details comments for the code. In addition, can you use clang-format for your code with this configuration so I can merge it into the master repo?

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