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

JointTrajectory: Don't use shortest_angular_distance for linear joints #623

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from

Conversation

bmagyar
Copy link
Member

@bmagyar bmagyar commented Nov 13, 2023

Fixes #432

Port #591 to Noetic

@bmagyar
Copy link
Member Author

bmagyar commented Nov 13, 2023

@steinmn could you please nod in agreement? ;)

Copy link

@steinmn steinmn left a comment

Choose a reason for hiding this comment

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

Nod :)

Copy link

@steinmn steinmn left a comment

Choose a reason for hiding this comment

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

On second thought, something doesn't look quite right here

Comment on lines +786 to 797
if (is_linear_[joint_index])
{
state_joint_error_.position[0] = desired_joint_state_.position[0] - current_state_.position[joint_index];
}
else
{
state_joint_error_.position[0] = angles::shortest_angular_distance(current_state_.position[joint_index],desired_joint_state_.position[0]);
}
state_joint_error_.velocity[0] = desired_joint_state_.velocity[0] - current_state_.velocity[joint_index];
state_joint_error_.acceleration[0] = 0.0;

state_error_.position[joint_index] = angles::shortest_angular_distance(current_state_.position[joint_index],desired_joint_state_.position[0]);
Copy link

Choose a reason for hiding this comment

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

Suggested change
if (is_linear_[joint_index])
{
state_joint_error_.position[0] = desired_joint_state_.position[0] - current_state_.position[joint_index];
}
else
{
state_joint_error_.position[0] = angles::shortest_angular_distance(current_state_.position[joint_index],desired_joint_state_.position[0]);
}
state_joint_error_.velocity[0] = desired_joint_state_.velocity[0] - current_state_.velocity[joint_index];
state_joint_error_.acceleration[0] = 0.0;
state_error_.position[joint_index] = angles::shortest_angular_distance(current_state_.position[joint_index],desired_joint_state_.position[0]);
if (is_linear_[joint_index])
{
state_error_.position[joint_index] = desired_joint_state_.position[0] - current_state_.position[joint_index];
}
else
{
state_error_.position[joint_index] = angles::shortest_angular_distance(current_state_.position[joint_index],desired_joint_state_.position[0]);
}

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.

Does JointTrajectoryController assume that joints are rotational?
2 participants