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

Improve interface for forward kinematics #161

Merged
merged 11 commits into from
Mar 24, 2014
Merged

Improve interface for forward kinematics #161

merged 11 commits into from
Mar 24, 2014

Conversation

jslee02
Copy link
Member

@jslee02 jslee02 commented Mar 21, 2014

  • Rename functions pertain to generalized coordinate
  • Add setters for configurations, generalized velocities, and generalized accelerations to Skeleton and Joint

Here are some examples with improved API:

// We are able to set configurations, generalized velocity, and generalized acceleration to skeleton as
skeleton->setConfigs(q, false, false, false);  // Just store q to skeleton
skeleton->setConfigs(q, true, false, false);  // and also update transformations of body nodes
skeleton->setConfigs(q, true, true, false);  // and also update spacial velocities of body nodes
skeleton->setConfigs(q, true, true, true);  // and also update spacial accelerations of body nodes
skeleton->setGenVels(dq, true, false);  // Store generalized velocity and update spacial velocities of body nodes
skeleton->setGenAccs(dq, true);  // Store generalized acceleration, and update spacial accelerations and accelerations

// We are also able to set the values directly to the joints as
skeleton->getJoint("left_hip")->setConfigs(q, true, false, false);
skeleton->getJoint("left_hip")->setGenVels(dq, true, false);
skeleton->getJoint("left_hip")->setGenAccs(ddq, true);

// If you want to update the spacial values at once then
skeleton->setConfigs(q, false, false, false);
skeleton->setGenVels(dq, false, false);
skeleton->setGenAccs(ddq, false);
skeleton->computeForwardKinematics(true, true, true);

// If you want more simple way not considering performance, then you can just ignore all the Boolean flags as
skeleton->setConfigs(q);  // All the spacial values are updated as default
skeleton->getJoint("left_knee")->setConfigs(q);  // All the spacial values are updated as default

jslee02 added 8 commits March 19, 2014 20:35
- Type defendent program is not recommended
- Only workaround for Issue #122 use dynamic_cast but this should be gone once this issue is resolved
- Skeleton pointer is required to notice to the skeleton that joint values are changed
- The skeleton point is set by Joint::init() and the init() function called by BodyNode::init()
@jslee02 jslee02 added this to the Release DART 4.0 milestone Mar 21, 2014
@karenliu
Copy link
Member

How do you update spatial velocity if I give you a new position for a the joint? Do you compute the finite difference between the new and old joint positions?

@jslee02
Copy link
Member Author

jslee02 commented Mar 21, 2014

Joints contain position, velocity, and other generalized values inside them. If new joint position is set then spatial velocity is updated using the new position and the inside velocity.

On Mar 21, 2014, at 8:27 AM, Karen Liu notifications@github.com wrote:

How do you update spatial velocity if I give you a new position for a the joint? Do you compute the finite difference between the new and old joint positions?


Reply to this email directly or view it on GitHub.

jslee02 added a commit that referenced this pull request Mar 24, 2014
Improve interface for forward kinematics
@jslee02 jslee02 merged commit 4333550 into master Mar 24, 2014
@jslee02 jslee02 deleted the dynamics_api branch March 27, 2014 08:00
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