-
Notifications
You must be signed in to change notification settings - Fork 10
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
Feature/ik panda #340
Open
Joobz
wants to merge
12
commits into
master
Choose a base branch
from
feature/ik_panda
base: master
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Feature/ik panda #340
Changes from 1 commit
Commits
Show all changes
12 commits
Select commit
Hold shift + click to select a range
5b13133
test IK for Panda, initial check-in
dellaert 5197e23
Make fix/unfix methods const
dellaert ea19ce1
Removed logmap and use gtsam
dellaert 54b26c1
Add constraints for fixed links
dellaert 7e44402
initial values function prototype
Joobz e534344
Added new functions in kinematics
Joobz 9a55580
joint angle limits
Joobz 9c70904
Adressed comments
Joobz d2226e4
PoseGoals and addressed more comments
Joobz fdb0b63
Adressed comments
Joobz 0cf03b5
added gpmp and changed kinematics
54c72df
small update
Joobz File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -73,13 +73,13 @@ EqualityConstraints Kinematics::constraints<Slice>(const Slice& slice, | |
// Get an expression for the unknown link pose. | ||
Pose3_ bTcom(PoseKey(link->id(), slice.k)); | ||
|
||
// Kust make sure it does not move from its original rest pose | ||
// Just make sure it does not move from its original rest pose | ||
Pose3_ bMcom(link->bMcom()); | ||
|
||
// Create expression to calculate the error in tangent space | ||
auto constraint_expr = gtsam::logmap(bTcom, bMcom); | ||
|
||
// Add constriant | ||
// Add constraint | ||
constraints.emplace_shared<VectorExpressionEquality<6>>(constraint_expr, | ||
tolerance); | ||
} | ||
|
@@ -126,13 +126,20 @@ NonlinearFactorGraph Kinematics::poseGoalObjectives<Slice>( | |
const gtsam::Values& goal_poses) const { | ||
gtsam::NonlinearFactorGraph graph; | ||
|
||
for (const gtsam::Key& key : goal_poses.keys()) { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. No, that is not how you iterate over a map in c++ :-) So
|
||
const gtsam::Pose3& desired_pose = goal_poses.at<gtsam::Pose3>(key); | ||
// TODO(toni): use poseprior from unstable gtsam slam or create new | ||
// factors, to add pose from link7 | ||
graph.addPrior<gtsam::Pose3>(key, desired_pose, p_.p_cost_model); | ||
} | ||
|
||
// Add priors on link poses with desired poses from argument | ||
for (auto&& link : robot.links()) { | ||
Joobz marked this conversation as resolved.
Show resolved
Hide resolved
|
||
auto pose_key = PoseKey(link->id(), slice.k); | ||
if (goal_poses.exists(pose_key)) { | ||
const gtsam::Pose3& desired_pose = goal_poses.at<gtsam::Pose3>(pose_key); | ||
// TODO: use poseprior from unstable gtsam slam or create new factors, to | ||
// add pose from link7 | ||
// TODO(toni): use poseprior from unstable gtsam slam or create new | ||
// factors, to add pose from link7 | ||
graph.addPrior<gtsam::Pose3>(pose_key, desired_pose, p_.p_cost_model); | ||
} | ||
} | ||
|
@@ -148,9 +155,8 @@ NonlinearFactorGraph Kinematics::jointAngleObjectives<Slice>( | |
// Minimize the joint angles. | ||
for (auto&& joint : robot.joints()) { | ||
const gtsam::Key key = JointAngleKey(joint->id(), slice.k); | ||
double joint_mean = 0.0; | ||
if (mean.exists(key)) joint_mean = mean.at<double>(key); | ||
graph.addPrior<double>(key, joint_mean, p_.prior_q_cost_model); | ||
graph.addPrior<double>(key, (mean.exists(key) ? mean.at<double>(key) : 0.0), | ||
p_.prior_q_cost_model); | ||
} | ||
|
||
return graph; | ||
|
@@ -171,31 +177,27 @@ NonlinearFactorGraph Kinematics::jointAngleLimits<Slice>( | |
} | ||
|
||
template <> | ||
Values Kinematics::initialValues<Slice>( | ||
const Slice& slice, const Robot& robot, double gaussian_noise, | ||
const gtsam::Values& initial_joints) const { | ||
Values Kinematics::initialValues<Slice>(const Slice& slice, const Robot& robot, | ||
double gaussian_noise, | ||
const gtsam::Values& initial_joints, | ||
bool use_fk) const { | ||
Values values; | ||
|
||
auto sampler_noise_model = | ||
gtsam::noiseModel::Isotropic::Sigma(6, gaussian_noise); | ||
gtsam::Sampler sampler(sampler_noise_model); | ||
|
||
// Initialize all joint angles. | ||
bool any_value = false; | ||
for (auto&& joint : robot.joints()) { | ||
auto key = JointAngleKey(joint->id(), slice.k); | ||
double value; | ||
if (initial_joints.exists(key)) { | ||
value = initial_joints.at<double>(key); | ||
any_value = true; | ||
} else | ||
value = sampler.sample()[0]; | ||
InsertJointAngle(&values, joint->id(), slice.k, value); | ||
double angle = initial_joints.exists(key) ? initial_joints.at<double>(key) | ||
: sampler.sample()[0]; | ||
InsertJointAngle(&values, joint->id(), slice.k, angle); | ||
} | ||
|
||
// Maybe fk takes a long time, so only compute it if there was a given initial | ||
// joint value in this slice | ||
if (any_value) { | ||
if (use_fk) { | ||
// Initialize poses with fk of initialized values | ||
auto fk = robot.forwardKinematics(values, slice.k); | ||
for (auto&& link : robot.links()) { | ||
|
@@ -241,12 +243,12 @@ Values Kinematics::inverse<Slice>(const Slice& slice, const Robot& robot, | |
} | ||
|
||
template <> | ||
gtsam::Values Kinematics::inverseWithPose<Slice>( | ||
gtsam::Values Kinematics::inverse<Slice>( | ||
const Slice& slice, const Robot& robot, const gtsam::Values& goal_poses, | ||
const gtsam::Values& joint_priors) const { | ||
auto graph = this->graph(slice, robot); | ||
|
||
// Add prior on joint angles to constrain the solution | ||
// Add prior on joint angles to prefer solution close to our initial estimates | ||
graph.add(this->jointAngleObjectives(slice, robot, joint_priors)); | ||
|
||
// Add priors on link poses with desired poses from argument | ||
|
@@ -258,7 +260,7 @@ gtsam::Values Kinematics::inverseWithPose<Slice>( | |
// Robot kinematics constraints | ||
auto constraints = this->constraints(slice, robot); | ||
|
||
auto initial_values = this->initialValues(slice, robot, 0.1, joint_priors); | ||
auto initial_values = this->initialValues(slice, robot, 0.1, joint_priors, true); | ||
|
||
return this->optimize(graph, constraints, initial_values); | ||
} | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
What does this flag do? Please amend doxygen above