33 #include <exotica_core/task_initializer.h> 48 return scene_->GetKinematicTree().GetJointLimits();
64 W = Eigen::MatrixXd::Identity(
N,
N);
65 if (init.W.rows() > 0)
67 if (init.W.rows() ==
N)
69 W.diagonal() = init.W;
73 ThrowNamed(
"W dimension mismatch! Expected " <<
N <<
", got " << init.W.rows());
79 if (init.LowerBound.rows() ==
N)
81 scene_->GetKinematicTree().SetJointLimitsLower(init.LowerBound);
83 else if (init.LowerBound.rows() != 0)
85 ThrowNamed(
"Lower bound size incorrect! Expected " <<
N <<
" got " << init.LowerBound.rows());
87 if (init.UpperBound.rows() ==
N)
89 scene_->GetKinematicTree().SetJointLimitsUpper(init.UpperBound);
91 else if (init.UpperBound.rows() != 0)
93 ThrowNamed(
"Lower bound size incorrect! Expected " <<
N <<
" got " << init.UpperBound.rows());
109 for (
int i = 0; i <
tasks_.size(); ++i)
tasks_[i]->is_used =
false;
129 if (
cost.
tasks[i]->GetObjectName() == task_name)
134 ThrowPretty(
"Cannot get scalar task cost. Task Map '" << task_name <<
"' does not exist.");
164 for (
int i = 0; i <
tasks_.size(); ++i)
213 if (
cost.
tasks[i]->GetObjectName() == task_name)
220 ThrowPretty(
"Cannot set Goal. Task Map '" << task_name <<
"' does not exist.");
227 if (
cost.
tasks[i]->GetObjectName() == task_name)
234 ThrowPretty(
"Cannot set rho. Task Map '" << task_name <<
"' does not exist.");
241 if (
cost.
tasks[i]->GetObjectName() == task_name)
246 ThrowPretty(
"Cannot get Goal. Task Map '" << task_name <<
"' does not exist.");
253 if (
cost.
tasks[i]->GetObjectName() == task_name)
258 ThrowPretty(
"Cannot get rho. Task Map '" << task_name <<
"' does not exist.");
272 ThrowPretty(
"Cannot set Goal. Task Map '" << task_name <<
"' does not exist.");
286 ThrowPretty(
"Cannot set rho. Task Map '" << task_name <<
"' does not exist.");
298 ThrowPretty(
"Cannot get Goal. Task Map '" << task_name <<
"' does not exist.");
310 ThrowPretty(
"Cannot get rho. Task Map '" << task_name <<
"' does not exist.");
324 ThrowPretty(
"Cannot set Goal. Task Map '" << task_name <<
"' does not exist.");
338 ThrowPretty(
"Cannot set rho. Task Map '" << task_name <<
"' does not exist.");
350 ThrowPretty(
"Cannot get Goal. Task Map '" << task_name <<
"' does not exist.");
362 ThrowPretty(
"Cannot get rho. Task Map '" << task_name <<
"' does not exist.");
367 std::cout.precision(4);
368 bool succeeded =
true;
372 Eigen::VectorXd
x =
scene_->GetKinematicTree().GetControlledState();
373 auto bounds =
scene_->GetKinematicTree().GetJointLimits();
376 constexpr
double tolerance = 1.e-3;
377 for (
unsigned int i = 0; i <
N; ++i)
379 if (x(i) < bounds(i, 0) - tolerance || x(i) > bounds(i, 1) + tolerance)
381 if (
debug_)
HIGHLIGHT_NAMED(
"EndPoseProblem::IsValid",
"Out of bounds (joint #" << i <<
"): " << bounds(i, 0) <<
" < " << x(i) <<
" < " << bounds(i, 1));
std::vector< TaskVectorEntry > map
KinematicRequestFlags flags_
Arbitrarily constrained end-pose problem implementation.
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
unsigned int number_of_problem_updates_
Eigen::MatrixXd GetInequalityJacobian()
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
void SetZero(const int n)
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
virtual ~EndPoseProblem()
Eigen::VectorXd GetInequality()
double GetRho(const std::string &task_name)
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
void Update(Eigen::VectorXdRefConst x)
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
void SetRhoNEQ(const std::string &task_name, const double &rho)
void SetRhoEQ(const std::string &task_name, const double &rho)
Eigen::VectorXd GetGoal(const std::string &task_name)
Eigen::RowVectorXd GetScalarJacobian()
double GetRhoEQ(const std::string &task_name)
void SetRho(const std::string &task_name, const double &rho)
Eigen::MatrixXd GetBounds() const
void PreUpdate() override
Eigen::MatrixXd GetEqualityJacobian()
EndPoseProblemInitializer parameters_
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
void Instantiate(const EndPoseProblemInitializer &init) override
#define HIGHLIGHT_NAMED(name, x)
double GetScalarTaskCost(const std::string &task_name) const
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
double GetRhoNEQ(const std::string &task_name)
Eigen::VectorXd GetEquality()
std::vector< TaskIndexing > indexing
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_jacobian, HessianRefConst big_hessian)
bool IsValid() override
Evaluates whether the problem is valid.
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)