-
Notifications
You must be signed in to change notification settings - Fork 11
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
base: master
Are you sure you want to change the base?
Feature/ik panda #340
Changes from all commits
5b13133
5197e23
ea19ce1
54b26c1
7e44402
e534344
9a55580
9c70904
d2226e4
fdb0b63
0cf03b5
54c72df
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -65,6 +65,53 @@ struct ContactGoal { | |
///< Map of link name to ContactGoal | ||
using ContactGoals = std::vector<ContactGoal>; | ||
|
||
/** | ||
* Similar to the previous struct ContactGoal but with poses instead of | ||
* points. | ||
* Desired world pose for a end-effector pose. | ||
* | ||
* This simple struct stores the robot link that holds the end-effector, the | ||
* end-effector's pose in the final link's CoM frame, and a `goal_pose` in | ||
* world coordinate frames. The goal is satisfied iff | ||
* `pose_on_link.predict(values, k) == goal_pose`. | ||
*/ | ||
struct PoseGoal { | ||
LinkSharedPtr ee_link; ///< Link that hold end-effector | ||
gtsam::Pose3 comTgoal; ///< Goal pose in link's CoM frame. | ||
gtsam::Pose3 wTgoal; ///< Goal pose in world frame. | ||
|
||
/// Constructor | ||
PoseGoal(const LinkSharedPtr& ee_link, const gtsam::Pose3& comTgoal, | ||
const gtsam::Pose3& wTgoal) | ||
: ee_link(ee_link), comTgoal(comTgoal), wTgoal(wTgoal) {} | ||
|
||
/// Return link associated with contact pose. | ||
const LinkSharedPtr& link() const { return ee_link; } | ||
|
||
/// Return CoM pose needed to achieve goal pose. | ||
const gtsam::Pose3 wTcom() const { | ||
return wTgoal.compose(comTgoal.inverse()); | ||
} | ||
|
||
/// Print to stream. | ||
friend std::ostream& operator<<(std::ostream& os, const PoseGoal& cg); | ||
|
||
/// GTSAM-style print, works with wrapper. | ||
void print(const std::string& s) const; | ||
|
||
/** | ||
* @fn Check that the contact goal has been achieved for given values. | ||
* @param values a GTSAM Values instance that should contain link pose. | ||
* @param k time step to check (default 0). | ||
* @param tol tolerance in 3D (default 1e-9). | ||
*/ | ||
bool satisfied(const gtsam::Values& values, size_t k = 0, | ||
double tol = 1e-9) const; | ||
}; | ||
|
||
///< Map of time to PoseGoal | ||
using PoseGoals = std::map<size_t, PoseGoal>; | ||
|
||
/// Noise models etc specific to Kinematics class | ||
struct KinematicsParameters : public OptimizationParameters { | ||
using Isotropic = gtsam::noiseModel::Isotropic; | ||
|
@@ -73,10 +120,10 @@ struct KinematicsParameters : public OptimizationParameters { | |
prior_q_cost_model; // joint angle prior factor | ||
|
||
// TODO(yetong): replace noise model with tolerance. | ||
KinematicsParameters() | ||
: p_cost_model(Isotropic::Sigma(6, 1e-4)), | ||
g_cost_model(Isotropic::Sigma(3, 0.01)), | ||
prior_q_cost_model(Isotropic::Sigma(1, 0.5)) {} | ||
KinematicsParameters(double p_cost_model_sigma = 1e-4, double g_cost_model_sigma = 1e-2, double prior_q_cost_model_sigma = 0.5) | ||
: p_cost_model(Isotropic::Sigma(6, p_cost_model_sigma)), | ||
g_cost_model(Isotropic::Sigma(3, g_cost_model_sigma)), | ||
prior_q_cost_model(Isotropic::Sigma(1, prior_q_cost_model_sigma)) {} | ||
}; | ||
|
||
/// All things kinematics, zero velocities/twists, and no forces. | ||
|
@@ -131,29 +178,61 @@ class Kinematics : public Optimizer { | |
EqualityConstraints pointGoalConstraints( | ||
const CONTEXT& context, const ContactGoals& contact_goals) const; | ||
|
||
/** | ||
* @fn Create a pose prior for a given link for each given pose. | ||
* @param context Slice or Interval instance. | ||
* @param pose_goals an object of PoseGoals: map of time k to desired pose at | ||
* that time, which will be used as mean of the prior | ||
* @returns graph with pose goal factors. | ||
*/ | ||
template <class CONTEXT> | ||
gtsam::NonlinearFactorGraph poseGoalObjectives( | ||
const CONTEXT& context, const PoseGoals& pose_goals) const; | ||
|
||
/** | ||
* @fn Factors that minimize joint angles. | ||
* @param context Slice or Interval instance. | ||
* @param robot Robot specification from URDF/SDF. | ||
* @param joint_priors Values where the mean of the priors is specified. The | ||
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. Same comment. You use Values. Does that mean in your case you specify different priors for every time step? Or, is it simply robot-specific in which case aa std::map with joint indices would be the right thing. I already commented on this but not getting ansers. And, answers should end up in the documentation... |
||
* default is an empty Values, meaning that the means will default to 0. | ||
* @returns graph with prior factors on joint angles. | ||
*/ | ||
template <class CONTEXT> | ||
gtsam::NonlinearFactorGraph jointAngleObjectives(const CONTEXT& context, | ||
const Robot& robot) const; | ||
gtsam::NonlinearFactorGraph jointAngleObjectives( | ||
const CONTEXT& context, const Robot& robot, | ||
const gtsam::Values& joint_priors = gtsam::Values()) const; | ||
gchenfc marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
/** | ||
* @fn Factors that enforce joint angle limits. | ||
* @param context Slice or Interval instance. | ||
* @param robot Robot specification from URDF/SDF. | ||
* @return graph with prior factors on joint angles. | ||
*/ | ||
template <class CONTEXT> | ||
gtsam::NonlinearFactorGraph jointAngleLimits(const CONTEXT& context, | ||
const Robot& robot) const; | ||
|
||
/** | ||
* @fn Initialize kinematics. | ||
* | ||
* Use wTcom for poses and zero-mean noise for joint angles. | ||
* If no values in initial_joints are given, use wTcom for poses and zero-mean | ||
* noise for joint angles. | ||
* If values are given, initialize joints with their given values, and | ||
* zero-mean noise to the ones that without a given value. Poses are | ||
* initialized with their fk values. | ||
* | ||
* | ||
* @param context Slice or Interval instance. | ||
* @param robot Robot specification from URDF/SDF. | ||
* @param gaussian_noise time step to check (default 0.1). | ||
* @param initial_joints initial values for joints | ||
* @returns values with identity poses and zero joint angles. | ||
*/ | ||
template <class CONTEXT> | ||
gtsam::Values initialValues(const CONTEXT& context, const Robot& robot, | ||
double gaussian_noise = 0.1) const; | ||
gtsam::Values initialValues( | ||
const CONTEXT& context, const Robot& robot, double gaussian_noise = 0.1, | ||
const gtsam::Values& initial_joints = gtsam::Values(), | ||
bool use_fk = false) const; | ||
|
||
/** | ||
* @fn Inverse kinematics given a set of contact goals. | ||
|
@@ -169,6 +248,21 @@ class Kinematics : public Optimizer { | |
const ContactGoals& contact_goals, | ||
bool contact_goals_as_constraints = true) const; | ||
|
||
/** | ||
* @fn Inverse kinematics given a set of desired poses | ||
* @fn This function does inverse kinematics separately on each slice | ||
* @param context Slice or Interval instance | ||
* @param robot Robot specification from URDF/SDF | ||
* @param pose_goals goals for EE poses | ||
* @param joint_priors optional argument to put priors centered on given | ||
* values. If empty, the priors will be centered on the origin | ||
* @return values with poses and joint angles | ||
*/ | ||
template <class CONTEXT> | ||
gtsam::Values inverse( | ||
const CONTEXT& context, const Robot& robot, const PoseGoals& pose_goals, | ||
const gtsam::Values& joint_priors = gtsam::Values()) const; | ||
gchenfc marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
/** | ||
* Interpolate using inverse kinematics: the goals are linearly interpolated. | ||
* @param context Interval instance | ||
|
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.
is it possible to have multiple pose goals for a single timestep? In which case maybe
std::map<size_t, std::vector<PoseGoal>>
would be more appropriate? Or if you don't need it I guess you can leave it.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.
Not in the painting case, only one pose per timestep is necessary, I think having multiple poses per timestep on a 7-DoF doesn't make much sense as we would be over constraining the problem, right?