Go to the documentation of this file.
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();
377 for (
unsigned int i = 0; i <
N; ++i)
381 if (
debug_)
HIGHLIGHT_NAMED(
"EndPoseProblem::IsValid",
"Out of bounds (joint #" << i <<
"): " << bounds(i, 0) <<
" < " <<
x(i) <<
" < " << bounds(i, 1));
unsigned int number_of_problem_updates_
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_jacobian, HessianRefConst big_hessian)
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
void SetRhoEQ(const std::string &task_name, const double &rho)
EndPoseProblemInitializer parameters_
KinematicRequestFlags flags_
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.
Eigen::VectorXd GetInequality()
void Update(Eigen::VectorXdRefConst x)
void SetGoalNEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Eigen::MatrixXd GetBounds() const
void SetGoalEQ(const std::string &task_name, Eigen::VectorXdRefConst goal)
Eigen::VectorXd GetGoal(const std::string &task_name)
#define HIGHLIGHT_NAMED(name, x)
Eigen::VectorXd GetEquality()
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
virtual ~EndPoseProblem()
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Eigen::VectorXd GetGoalEQ(const std::string &task_name)
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
std::vector< TaskVectorEntry > map
double GetScalarTaskCost(const std::string &task_name) const
std::vector< TaskIndexing > indexing
double GetRhoEQ(const std::string &task_name)
Eigen::MatrixXd GetEqualityJacobian()
Arbitrarily constrained end-pose problem implementation.
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Eigen::VectorXd GetGoalNEQ(const std::string &task_name)
void init(const M_string &remappings)
double GetRhoNEQ(const std::string &task_name)
void SetRho(const std::string &task_name, const double &rho)
void PreUpdate() override
Eigen::RowVectorXd GetScalarJacobian()
Eigen::MatrixXd GetInequalityJacobian()
double GetRho(const std::string &task_name)
void SetZero(const int n)
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02