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

Fixed velocity controller #450

Merged
merged 3 commits into from
Jan 7, 2025
Merged

Fixed velocity controller #450

merged 3 commits into from
Jan 7, 2025

Conversation

ahcorde
Copy link
Collaborator

@ahcorde ahcorde commented Dec 3, 2024

Just testing a PR I noticed that velocity controllers were not working. I made this quick fix but I'm not sure if this will break other users

@christophfroehlich any thoughts?

Signed-off-by: Alejandro Hernández Cordero <[email protected]>
@ahcorde ahcorde self-assigned this Dec 3, 2024
@ahcorde
Copy link
Collaborator Author

ahcorde commented Dec 3, 2024

@azeey do you know why the JointVelocityCmd is destroyed ? and I have to create a new one every iteration ?

this is not happening with position and effort

@@ -654,7 +654,7 @@ hardware_interface::return_type GazeboSimSystem::write(
{
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[i].sim_joint,
sim::components::JointVelocityCmd({0}));
sim::components::JointVelocityCmd({this->dataPtr->joints_[i].joint_velocity_cmd}));
Copy link
Contributor

Choose a reason for hiding this comment

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

This can be simplified by using the SetComponentData function, so it would just look like:

this->dataPtr->ecm->SetComponentData(this->dataPtr->joints_[i].sim_joint, {this->dataPtr->joints_[i].sim_joint})

replacing the entire if/else block starting with if (!this->dataPtr->ecm->Component<sim::components::JointVelocityCmd>( this->dataPtr->joints_[i].sim_joint))

@christophfroehlich christophfroehlich linked an issue Jan 7, 2025 that may be closed by this pull request
@ahcorde ahcorde requested a review from azeey January 7, 2025 14:01
@ahcorde ahcorde merged commit f9b4e7f into rolling Jan 7, 2025
4 checks passed
@ahcorde ahcorde deleted the ahcorde/rolling/velocity_fix branch January 7, 2025 15:48
Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

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

Thanks @azeey @ahcorde
I can confirm that my reported issue is fixed now.

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.

Velocity command interface is broken on rolling+ionic
3 participants