#include <unconstrained_end_pose_problem.h>
Public Member Functions | |
Eigen::VectorXd | GetGoal (const std::string &task_name) const |
Eigen::VectorXd | GetNominalPose () const |
double | GetRho (const std::string &task_name) const |
double | GetScalarCost () const |
Eigen::RowVectorXd | GetScalarJacobian () const |
double | GetScalarTaskCost (const std::string &task_name) const |
GetScalarTaskCost get weighted sum-of-squares of cost vector. More... | |
int | GetTaskId (const std::string &task_name) const |
void | Instantiate (const UnconstrainedEndPoseProblemInitializer &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 | SetNominalPose (Eigen::VectorXdRefConst qNominal_in) |
void | SetRho (const std::string &task_name, const double &rho) |
UnconstrainedEndPoseProblem () | |
void | Update (Eigen::VectorXdRefConst x) |
virtual | ~UnconstrainedEndPoseProblem () |
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< UnconstrainedEndPoseProblemInitializer > | |
std::vector< Initializer > | GetAllTemplates () const override |
Initializer | GetInitializerTemplate () override |
const UnconstrainedEndPoseProblemInitializer & | GetParameters () const |
void | InstantiateInternal (const Initializer &init) override |
Public Attributes | |
EndPoseTask | cost |
Hessian | hessian |
Eigen::MatrixXd | jacobian |
int | length_jacobian |
int | length_Phi |
int | num_tasks |
TaskSpaceVector | Phi |
Eigen::VectorXd | q_nominal |
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< UnconstrainedEndPoseProblemInitializer > | |
UnconstrainedEndPoseProblemInitializer | parameters_ |
Definition at line 40 of file unconstrained_end_pose_problem.h.
exotica::UnconstrainedEndPoseProblem::UnconstrainedEndPoseProblem | ( | ) |
Definition at line 37 of file unconstrained_end_pose_problem.cpp.
|
virtualdefault |
Eigen::VectorXd exotica::UnconstrainedEndPoseProblem::GetGoal | ( | const std::string & | task_name | ) | const |
Definition at line 176 of file unconstrained_end_pose_problem.cpp.
Eigen::VectorXd exotica::UnconstrainedEndPoseProblem::GetNominalPose | ( | ) | const |
Definition at line 200 of file unconstrained_end_pose_problem.cpp.
double exotica::UnconstrainedEndPoseProblem::GetRho | ( | const std::string & | task_name | ) | const |
Definition at line 188 of file unconstrained_end_pose_problem.cpp.
double exotica::UnconstrainedEndPoseProblem::GetScalarCost | ( | ) | const |
Definition at line 86 of file unconstrained_end_pose_problem.cpp.
Eigen::RowVectorXd exotica::UnconstrainedEndPoseProblem::GetScalarJacobian | ( | ) | const |
Definition at line 91 of file unconstrained_end_pose_problem.cpp.
double exotica::UnconstrainedEndPoseProblem::GetScalarTaskCost | ( | const std::string & | task_name | ) | const |
GetScalarTaskCost get weighted sum-of-squares of cost vector.
task_name | valid task |
Definition at line 96 of file unconstrained_end_pose_problem.cpp.
int exotica::UnconstrainedEndPoseProblem::GetTaskId | ( | const std::string & | task_name | ) | const |
Definition at line 214 of file unconstrained_end_pose_problem.cpp.
|
overridevirtual |
Reimplemented from exotica::Instantiable< UnconstrainedEndPoseProblemInitializer >.
Definition at line 44 of file unconstrained_end_pose_problem.cpp.
|
inlineoverridevirtual |
Evaluates whether the problem is valid.
Reimplemented from exotica::PlanningProblem.
Definition at line 49 of file unconstrained_end_pose_problem.h.
|
overridevirtual |
Reimplemented from exotica::PlanningProblem.
Definition at line 79 of file unconstrained_end_pose_problem.cpp.
void exotica::UnconstrainedEndPoseProblem::SetGoal | ( | const std::string & | task_name, |
Eigen::VectorXdRefConst | goal | ||
) |
Definition at line 148 of file unconstrained_end_pose_problem.cpp.
void exotica::UnconstrainedEndPoseProblem::SetNominalPose | ( | Eigen::VectorXdRefConst | qNominal_in | ) |
Definition at line 205 of file unconstrained_end_pose_problem.cpp.
void exotica::UnconstrainedEndPoseProblem::SetRho | ( | const std::string & | task_name, |
const double & | rho | ||
) |
Definition at line 162 of file unconstrained_end_pose_problem.cpp.
void exotica::UnconstrainedEndPoseProblem::Update | ( | Eigen::VectorXdRefConst | x | ) |
Definition at line 102 of file unconstrained_end_pose_problem.cpp.
EndPoseTask exotica::UnconstrainedEndPoseProblem::cost |
Definition at line 69 of file unconstrained_end_pose_problem.h.
Hessian exotica::UnconstrainedEndPoseProblem::hessian |
Definition at line 74 of file unconstrained_end_pose_problem.h.
Eigen::MatrixXd exotica::UnconstrainedEndPoseProblem::jacobian |
Definition at line 73 of file unconstrained_end_pose_problem.h.
int exotica::UnconstrainedEndPoseProblem::length_jacobian |
Definition at line 78 of file unconstrained_end_pose_problem.h.
int exotica::UnconstrainedEndPoseProblem::length_Phi |
Definition at line 77 of file unconstrained_end_pose_problem.h.
int exotica::UnconstrainedEndPoseProblem::num_tasks |
Definition at line 79 of file unconstrained_end_pose_problem.h.
TaskSpaceVector exotica::UnconstrainedEndPoseProblem::Phi |
Definition at line 72 of file unconstrained_end_pose_problem.h.
Eigen::VectorXd exotica::UnconstrainedEndPoseProblem::q_nominal |
Definition at line 75 of file unconstrained_end_pose_problem.h.
Eigen::MatrixXd exotica::UnconstrainedEndPoseProblem::W |
Definition at line 71 of file unconstrained_end_pose_problem.h.