Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_END_POSE_PROBLEM_H_
31 #define EXOTICA_CORE_END_POSE_PROBLEM_H_
36 #include <exotica_core/end_pose_problem_initializer.h>
47 void Instantiate(
const EndPoseProblemInitializer& init)
override;
52 void SetRho(
const std::string& task_name,
const double& rho);
53 Eigen::VectorXd
GetGoal(
const std::string& task_name);
54 double GetRho(
const std::string& task_name);
56 void SetRhoEQ(
const std::string& task_name,
const double& rho);
57 Eigen::VectorXd
GetGoalEQ(
const std::string& task_name);
58 double GetRhoEQ(
const std::string& task_name);
60 void SetRhoNEQ(
const std::string& task_name,
const double& rho);
61 Eigen::VectorXd
GetGoalNEQ(
const std::string& task_name);
62 double GetRhoNEQ(
const std::string& task_name);
91 #endif // EXOTICA_CORE_END_POSE_PROBLEM_H_
Hessian hessian
Definition: end_pose_problem.h:81
void SetRhoEQ(const std::string &task_name, const double &rho)
void Instantiate(const EndPoseProblemInitializer &init) override
void SetRhoNEQ(const std::string &task_name, const double &rho)
bool IsValid() override
Evaluates whether the problem is valid.
std::shared_ptr< exotica::EndPoseProblem > EndPoseProblemPtr
Definition: end_pose_problem.h:88
Eigen::VectorXd GetInequality()
void Update(Eigen::VectorXdRefConst x)
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Eigen::MatrixXd GetBounds() const
virtual ~EndPoseProblem()
Definition: property.h:110
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Definition: cartpole_dynamics_solver.h:38
bool use_bounds
Definition: end_pose_problem.h:86
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
Definition: conversions.h:154
Eigen::VectorXd GetGoal(const std::string &task_name)
Eigen::MatrixXd W
Definition: end_pose_problem.h:78
int num_tasks
Definition: end_pose_problem.h:85
EndPoseTask cost
Definition: end_pose_problem.h:74
Eigen::VectorXd GetEquality()
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
Eigen::MatrixXd jacobian
Definition: end_pose_problem.h:80
Definition: task_space_vector.h:50
double GetScalarTaskCost(const std::string &task_name) const
double GetRhoEQ(const std::string &task_name)
Eigen::MatrixXd GetEqualityJacobian()
TaskSpaceVector Phi
Definition: end_pose_problem.h:79
EndPoseTask equality
Definition: end_pose_problem.h:76
Arbitrarily constrained end-pose problem implementation.
Definition: end_pose_problem.h:41
Definition: planning_problem.h:64
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
int length_jacobian
Definition: end_pose_problem.h:84
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
double GetRhoNEQ(const std::string &task_name)
void SetRho(const std::string &task_name, const double &rho)
void PreUpdate() override
EndPoseTask inequality
Definition: end_pose_problem.h:75
Eigen::RowVectorXd GetScalarJacobian()
int length_Phi
Definition: end_pose_problem.h:83
Eigen::MatrixXd GetInequalityJacobian()
double GetRho(const std::string &task_name)