Go to the documentation of this file.
41 if (
init.LowerBound.rows() ==
N)
43 scene_->GetKinematicTree().SetJointLimitsLower(
init.LowerBound);
45 else if (
init.LowerBound.rows() != 0)
47 ThrowNamed(
"Lower bound size incorrect! Expected " <<
N <<
" got " <<
init.LowerBound.rows());
49 if (
init.UpperBound.rows() ==
N)
51 scene_->GetKinematicTree().SetJointLimitsUpper(
init.UpperBound);
53 else if (
init.UpperBound.rows() != 0)
55 ThrowNamed(
"Lower bound size incorrect! Expected " <<
N <<
" got " <<
init.UpperBound.rows());
69 for (
int i = 0; i <
tasks_.size(); ++i)
tasks_[i]->is_used =
false;
77 for (
int i = 0; i < T_; ++i) kinematic_solutions_[i] = std::make_shared<KinematicResponse>(*
scene_->GetKinematicTree().GetKinematicResponse());
167 Phi.assign(
T_, y_ref_);
169 x.assign(
T_, Eigen::VectorXd::Zero(
N));
170 xdiff.assign(
T_, Eigen::VectorXd::Zero(
N));
193 bool succeeded =
true;
194 auto bounds =
scene_->GetKinematicTree().GetJointLimits();
196 std::cout.precision(4);
199 for (
int t = 0;
t <
T_; ++
t)
204 for (
int i = 0; i <
N; ++i)
209 if (
debug_)
HIGHLIGHT_NAMED(
"TimeIndexedProblem::IsValid",
"State at timestep " <<
t <<
" is out of bounds: joint #" << i <<
": " << bounds(i, 0) <<
" < " <<
x[
t](i) <<
" < " << bounds(i, 1));
unsigned int number_of_problem_updates_
void ReinitializeVariables(int _T, std::shared_ptr< PlanningProblem > _prob, const TaskSpaceVector &_Phi)
std::vector< Eigen::VectorXd > initial_trajectory_
void AppendVector(std::vector< Val > &orig, const std::vector< Val > &extra)
BoundedTimeIndexedProblemInitializer parameters_
KinematicRequestFlags flags_
std::vector< Eigen::VectorXd > x
Current internal problem state.
Bound constrained time-indexed problem.
void Update(const TaskSpaceVector &big_Phi, Eigen::MatrixXdRefConst big_dPhi_dx, Eigen::MatrixXdRefConst big_dPhi_du, HessianRefConst big_ddPhi_ddx, HessianRefConst big_ddPhi_ddu, HessianRefConst big_ddPhi_dxdu, int t)
bool IsValid() override
Evaluates whether the problem is valid.
std::vector< Eigen::MatrixXd > jacobian
void ValidateTimeIndex(int &t_in) const
Checks the desired time index for bounds and supports -1 indexing.
void UpdateMultipleTaskKinematics(std::vector< std::shared_ptr< KinematicResponse >> responses)
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
#define HIGHLIGHT_NAMED(name, x)
void ReinitializeVariables() override
int T_
Number of time steps.
Eigen::VectorXd xdiff_max_
Maximum change in the variables in a single timestep tau_. Gets set/updated via SetJointVelocityLimit...
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
double tau_
Time step duration.
#define REGISTER_PROBLEM_TYPE(TYPE, DERIV)
std::vector< Hessian > hessian
void Instantiate(const BoundedTimeIndexedProblemInitializer &init) override
Instantiates the problem from an Initializer.
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
void PreUpdate() override
Updates internal variables before solving, e.g., after setting new values for Rho.
std::vector< TaskVectorEntry > map
virtual void Initialize(const std::vector< exotica::Initializer > &inits, std::shared_ptr< PlanningProblem > prob, TaskSpaceVector &Phi)
void Update(Eigen::VectorXdRefConst x, int t) override
Updates an individual timestep from a given state vector.
TimeIndexedTask cost
Cost task.
std::vector< TaskSpaceVector > Phi
std::vector< Eigen::VectorXd > xdiff
virtual Eigen::VectorXd ApplyStartState(bool update_traj=true)
Eigen::VectorXd q_dot_max_
Joint velocity limit (rad/s)
std::vector< std::shared_ptr< KinematicResponse > > kinematic_solutions_
void init(const M_string &remappings)
double ct
Normalisation of scalar cost and Jacobian over trajectory length.
geometry_msgs::TransformStamped t
void SetZero(const int n)
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02