Arbitrarily constrained end-pose problem implementation. More...
#include <end_pose_problem.h>
Public Member Functions | |
EndPoseProblem () | |
Eigen::MatrixXd | GetBounds () const |
Eigen::VectorXd | GetEquality () |
Eigen::MatrixXd | GetEqualityJacobian () |
Eigen::VectorXd | GetGoal (const std::string &task_name) |
Eigen::VectorXd | GetGoalEQ (const std::string &task_name) |
Eigen::VectorXd | GetGoalNEQ (const std::string &task_name) |
Eigen::VectorXd | GetInequality () |
Eigen::MatrixXd | GetInequalityJacobian () |
double | GetRho (const std::string &task_name) |
double | GetRhoEQ (const std::string &task_name) |
double | GetRhoNEQ (const std::string &task_name) |
double | GetScalarCost () |
Eigen::RowVectorXd | GetScalarJacobian () |
double | GetScalarTaskCost (const std::string &task_name) const |
void | Instantiate (const EndPoseProblemInitializer &init) override |
bool | IsValid () override |
Evaluates whether the problem is valid. More... | |
void | PreUpdate () override |
void | SetGoal (const std::string &task_name, Eigen::VectorXdRefConst goal) |
void | SetGoalEQ (const std::string &task_name, Eigen::VectorXdRefConst goal) |
void | SetGoalNEQ (const std::string &task_name, Eigen::VectorXdRefConst goal) |
void | SetRho (const std::string &task_name, const double &rho) |
void | SetRhoEQ (const std::string &task_name, const double &rho) |
void | SetRhoNEQ (const std::string &task_name, const double &rho) |
void | Update (Eigen::VectorXdRefConst x) |
virtual | ~EndPoseProblem () |
Public Member Functions inherited from exotica::PlanningProblem | |
virtual Eigen::VectorXd | ApplyStartState (bool update_traj=true) |
int | get_num_controls () const |
int | get_num_positions () const |
! Dimension of planning problem. TODO: Update from positions/velocities/controls and make private. More... | |
int | get_num_velocities () const |
std::pair< std::vector< double >, std::vector< double > > | GetCostEvolution () const |
double | GetCostEvolution (int index) const |
KinematicRequestFlags | GetFlags () const |
int | GetNumberOfIterations () const |
unsigned int | GetNumberOfProblemUpdates () const |
ScenePtr | GetScene () const |
Eigen::VectorXd | GetStartState () const |
double | GetStartTime () const |
TaskMapMap & | GetTaskMaps () |
TaskMapVec & | GetTasks () |
void | InstantiateBase (const Initializer &init) override |
PlanningProblem () | |
std::string | Print (const std::string &prepend) const override |
void | ResetCostEvolution (size_t size) |
void | ResetNumberOfProblemUpdates () |
void | SetCostEvolution (int index, double value) |
void | SetStartState (Eigen::VectorXdRefConst x) |
void | SetStartTime (double t) |
virtual | ~PlanningProblem () |
Public Member Functions inherited from exotica::Object | |
std::string | GetObjectName () |
void | InstantiateObject (const Initializer &init) |
Object () | |
virtual std::string | type () const |
Type Information wrapper: must be virtual so that it is polymorphic... More... | |
virtual | ~Object () |
Public Member Functions inherited from exotica::InstantiableBase | |
InstantiableBase ()=default | |
virtual | ~InstantiableBase ()=default |
Public Member Functions inherited from exotica::Instantiable< EndPoseProblemInitializer > | |
std::vector< Initializer > | GetAllTemplates () const override |
Initializer | GetInitializerTemplate () override |
const EndPoseProblemInitializer & | GetParameters () const |
void | InstantiateInternal (const Initializer &init) override |
Public Attributes | |
EndPoseTask | cost |
EndPoseTask | equality |
Hessian | hessian |
EndPoseTask | inequality |
Eigen::MatrixXd | jacobian |
int | length_jacobian |
int | length_Phi |
int | num_tasks |
TaskSpaceVector | Phi |
bool | use_bounds |
Eigen::MatrixXd | W |
Public Attributes inherited from exotica::PlanningProblem | |
int | N = 0 |
double | t_start |
TerminationCriterion | termination_criterion |
Public Attributes inherited from exotica::Object | |
bool | debug_ |
std::string | ns_ |
std::string | object_name_ |
Additional Inherited Members | |
Protected Member Functions inherited from exotica::PlanningProblem | |
void | UpdateMultipleTaskKinematics (std::vector< std::shared_ptr< KinematicResponse >> responses) |
void | UpdateTaskKinematics (std::shared_ptr< KinematicResponse > response) |
Protected Attributes inherited from exotica::PlanningProblem | |
std::vector< std::pair< std::chrono::high_resolution_clock::time_point, double > > | cost_evolution_ |
KinematicRequestFlags | flags_ = KinematicRequestFlags::KIN_FK |
unsigned int | number_of_problem_updates_ = 0 |
ScenePtr | scene_ |
Eigen::VectorXd | start_state_ |
TaskMapMap | task_maps_ |
TaskMapVec | tasks_ |
Protected Attributes inherited from exotica::Instantiable< EndPoseProblemInitializer > | |
EndPoseProblemInitializer | parameters_ |
Arbitrarily constrained end-pose problem implementation.
Definition at line 41 of file end_pose_problem.h.
exotica::EndPoseProblem::EndPoseProblem | ( | ) |
Definition at line 39 of file end_pose_problem.cpp.
|
virtualdefault |
Eigen::MatrixXd exotica::EndPoseProblem::GetBounds | ( | ) | const |
Definition at line 46 of file end_pose_problem.cpp.
Eigen::VectorXd exotica::EndPoseProblem::GetEquality | ( | ) |
Definition at line 137 of file end_pose_problem.cpp.
Eigen::MatrixXd exotica::EndPoseProblem::GetEqualityJacobian | ( | ) |
Definition at line 142 of file end_pose_problem.cpp.
Eigen::VectorXd exotica::EndPoseProblem::GetGoal | ( | const std::string & | task_name | ) |
Definition at line 237 of file end_pose_problem.cpp.
Eigen::VectorXd exotica::EndPoseProblem::GetGoalEQ | ( | const std::string & | task_name | ) |
Definition at line 289 of file end_pose_problem.cpp.
Eigen::VectorXd exotica::EndPoseProblem::GetGoalNEQ | ( | const std::string & | task_name | ) |
Definition at line 341 of file end_pose_problem.cpp.
Eigen::VectorXd exotica::EndPoseProblem::GetInequality | ( | ) |
Definition at line 147 of file end_pose_problem.cpp.
Eigen::MatrixXd exotica::EndPoseProblem::GetInequalityJacobian | ( | ) |
Definition at line 152 of file end_pose_problem.cpp.
double exotica::EndPoseProblem::GetRho | ( | const std::string & | task_name | ) |
Definition at line 249 of file end_pose_problem.cpp.
double exotica::EndPoseProblem::GetRhoEQ | ( | const std::string & | task_name | ) |
Definition at line 301 of file end_pose_problem.cpp.
double exotica::EndPoseProblem::GetRhoNEQ | ( | const std::string & | task_name | ) |
Definition at line 353 of file end_pose_problem.cpp.
double exotica::EndPoseProblem::GetScalarCost | ( | ) |
Definition at line 115 of file end_pose_problem.cpp.
Eigen::RowVectorXd exotica::EndPoseProblem::GetScalarJacobian | ( | ) |
Definition at line 120 of file end_pose_problem.cpp.
double exotica::EndPoseProblem::GetScalarTaskCost | ( | const std::string & | task_name | ) | const |
Definition at line 125 of file end_pose_problem.cpp.
|
overridevirtual |
Reimplemented from exotica::Instantiable< EndPoseProblemInitializer >.
Definition at line 51 of file end_pose_problem.cpp.
|
overridevirtual |
Evaluates whether the problem is valid.
Reimplemented from exotica::PlanningProblem.
Definition at line 365 of file end_pose_problem.cpp.
|
overridevirtual |
Reimplemented from exotica::PlanningProblem.
Definition at line 106 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::SetGoal | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal | ||
) |
Definition at line 209 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::SetGoalEQ | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal | ||
) |
Definition at line 261 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::SetGoalNEQ | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal | ||
) |
Definition at line 313 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::SetRho | ( | const std::string & | task_name, |
const double & | rho | ||
) |
Definition at line 223 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::SetRhoEQ | ( | const std::string & | task_name, |
const double & | rho | ||
) |
Definition at line 275 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::SetRhoNEQ | ( | const std::string & | task_name, |
const double & | rho | ||
) |
Definition at line 327 of file end_pose_problem.cpp.
void exotica::EndPoseProblem::Update | ( | Eigen::VectorXdRefConst | x | ) |
Definition at line 157 of file end_pose_problem.cpp.
EndPoseTask exotica::EndPoseProblem::cost |
Definition at line 74 of file end_pose_problem.h.
EndPoseTask exotica::EndPoseProblem::equality |
Definition at line 76 of file end_pose_problem.h.
Hessian exotica::EndPoseProblem::hessian |
Definition at line 81 of file end_pose_problem.h.
EndPoseTask exotica::EndPoseProblem::inequality |
Definition at line 75 of file end_pose_problem.h.
Eigen::MatrixXd exotica::EndPoseProblem::jacobian |
Definition at line 80 of file end_pose_problem.h.
int exotica::EndPoseProblem::length_jacobian |
Definition at line 84 of file end_pose_problem.h.
int exotica::EndPoseProblem::length_Phi |
Definition at line 83 of file end_pose_problem.h.
int exotica::EndPoseProblem::num_tasks |
Definition at line 85 of file end_pose_problem.h.
TaskSpaceVector exotica::EndPoseProblem::Phi |
Definition at line 79 of file end_pose_problem.h.
bool exotica::EndPoseProblem::use_bounds |
Definition at line 86 of file end_pose_problem.h.
Eigen::MatrixXd exotica::EndPoseProblem::W |
Definition at line 78 of file end_pose_problem.h.