Go to the documentation of this file.
33 #include <exotica_core/task_initializer.h>
48 return scene_->GetKinematicTree().GetJointLimits();
63 W = Eigen::MatrixXd::Identity(
N,
N);
64 if (
init.W.rows() > 0)
66 if (
init.W.rows() ==
N)
68 W.diagonal() =
init.W;
72 ThrowNamed(
"W dimension mismatch! Expected " <<
N <<
", got " <<
init.W.rows());
78 if (
init.LowerBound.rows() ==
N)
80 scene_->GetKinematicTree().SetJointLimitsLower(
init.LowerBound);
82 else if (
init.LowerBound.rows() != 0)
84 ThrowNamed(
"Lower bound size incorrect! Expected " <<
N <<
" got " <<
init.LowerBound.rows());
86 if (
init.UpperBound.rows() ==
N)
88 scene_->GetKinematicTree().SetJointLimitsUpper(
init.UpperBound);
90 else if (
init.UpperBound.rows() != 0)
92 ThrowNamed(
"Lower bound size incorrect! Expected " <<
N <<
" got " <<
init.UpperBound.rows());
104 for (
int i = 0; i <
tasks_.size(); ++i)
tasks_[i]->is_used =
false;
122 if (
cost.
tasks[i]->GetObjectName() == task_name)
127 ThrowPretty(
"Cannot get scalar task cost. Task map '" << task_name <<
"' does not exist.");
137 for (
int i = 0; i <
tasks_.size(); ++i)
180 if (
cost.
tasks[i]->GetObjectName() == task_name)
187 ThrowPretty(
"Cannot set Goal. Task map '" << task_name <<
"' does not exist.");
194 if (
cost.
tasks[i]->GetObjectName() == task_name)
201 ThrowPretty(
"Cannot set rho. Task map '" << task_name <<
"' does not exist.");
208 if (
cost.
tasks[i]->GetObjectName() == task_name)
213 ThrowPretty(
"Cannot get Goal. Task map '" << task_name <<
"' does not exist.");
220 if (
cost.
tasks[i]->GetObjectName() == task_name)
225 ThrowPretty(
"Cannot get rho. Task map '" << task_name <<
"' does not exist.");
230 Eigen::VectorXd
x =
scene_->GetKinematicTree().GetControlledState();
231 Eigen::MatrixXd bounds =
scene_->GetKinematicTree().GetJointLimits();
233 std::cout.precision(4);
236 bool succeeded =
true;
237 for (
unsigned int i = 0; i <
N; ++i)
241 if (
debug_)
HIGHLIGHT_NAMED(
"BoundedEndPoseProblem::IsValid",
"Out of bounds (joint #" << i <<
"): " << bounds(i, 0) <<
" < " <<
x(i) <<
" < " << bounds(i, 1));
double GetScalarTaskCost(const std::string &task_name) const
Eigen::RowVectorXd GetScalarJacobian() const
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)
KinematicRequestFlags flags_
Eigen::VectorXd GetGoal(const std::string &task_name)
void Update(Eigen::VectorXdRefConst x)
virtual ~BoundedEndPoseProblem()
void SetGoal(const std::string &task_name, Eigen::VectorXdRefConst goal)
void PreUpdate() override
#define HIGHLIGHT_NAMED(name, x)
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
std::vector< TaskVectorEntry > map
std::vector< TaskIndexing > indexing
void Instantiate(const BoundedEndPoseProblemInitializer &init) override
bool IsValid() override
Evaluates whether the problem is valid.
Eigen::MatrixXd GetBounds() const
double GetRho(const std::string &task_name)
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Bound constrained end-pose problem implementation.
void SetRho(const std::string &task_name, const double &rho)
void init(const M_string &remappings)
double GetScalarCost() const
void SetZero(const int n)
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02