Public Member Functions | Public Attributes | List of all members
exotica::BoundedEndPoseProblem Class Reference

Bound constrained end-pose problem implementation. More...

#include <bounded_end_pose_problem.h>

Inheritance diagram for exotica::BoundedEndPoseProblem:
Inheritance graph
[legend]

Public Member Functions

 BoundedEndPoseProblem ()
 
Eigen::MatrixXd GetBounds () const
 
Eigen::VectorXd GetGoal (const std::string &task_name)
 
double GetRho (const std::string &task_name)
 
double GetScalarCost () const
 
Eigen::RowVectorXd GetScalarJacobian () const
 
double GetScalarTaskCost (const std::string &task_name) const
 
void Instantiate (const BoundedEndPoseProblemInitializer &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 SetRho (const std::string &task_name, const double &rho)
 
void Update (Eigen::VectorXdRefConst x)
 
virtual ~BoundedEndPoseProblem ()
 
- 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
 
TaskMapMapGetTaskMaps ()
 
TaskMapVecGetTasks ()
 
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
virtual std::vector< InitializerGetAllTemplates () const =0
 
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< BoundedEndPoseProblemInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const BoundedEndPoseProblemInitializer & 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::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< BoundedEndPoseProblemInitializer >
BoundedEndPoseProblemInitializer parameters_
 

Detailed Description

Bound constrained end-pose problem implementation.

Definition at line 41 of file bounded_end_pose_problem.h.

Constructor & Destructor Documentation

◆ BoundedEndPoseProblem()

exotica::BoundedEndPoseProblem::BoundedEndPoseProblem ( )

Definition at line 39 of file bounded_end_pose_problem.cpp.

◆ ~BoundedEndPoseProblem()

exotica::BoundedEndPoseProblem::~BoundedEndPoseProblem ( )
virtualdefault

Member Function Documentation

◆ GetBounds()

Eigen::MatrixXd exotica::BoundedEndPoseProblem::GetBounds ( ) const

Definition at line 46 of file bounded_end_pose_problem.cpp.

◆ GetGoal()

Eigen::VectorXd exotica::BoundedEndPoseProblem::GetGoal ( const std::string &  task_name)

Definition at line 204 of file bounded_end_pose_problem.cpp.

◆ GetRho()

double exotica::BoundedEndPoseProblem::GetRho ( const std::string &  task_name)

Definition at line 216 of file bounded_end_pose_problem.cpp.

◆ GetScalarCost()

double exotica::BoundedEndPoseProblem::GetScalarCost ( ) const

Definition at line 108 of file bounded_end_pose_problem.cpp.

◆ GetScalarJacobian()

Eigen::RowVectorXd exotica::BoundedEndPoseProblem::GetScalarJacobian ( ) const

Definition at line 113 of file bounded_end_pose_problem.cpp.

◆ GetScalarTaskCost()

double exotica::BoundedEndPoseProblem::GetScalarTaskCost ( const std::string &  task_name) const

Definition at line 118 of file bounded_end_pose_problem.cpp.

◆ Instantiate()

void exotica::BoundedEndPoseProblem::Instantiate ( const BoundedEndPoseProblemInitializer &  init)
overridevirtual

◆ IsValid()

bool exotica::BoundedEndPoseProblem::IsValid ( )
overridevirtual

Evaluates whether the problem is valid.

Reimplemented from exotica::PlanningProblem.

Definition at line 228 of file bounded_end_pose_problem.cpp.

◆ PreUpdate()

void exotica::BoundedEndPoseProblem::PreUpdate ( )
overridevirtual

Reimplemented from exotica::PlanningProblem.

Definition at line 101 of file bounded_end_pose_problem.cpp.

◆ SetGoal()

void exotica::BoundedEndPoseProblem::SetGoal ( const std::string &  task_name,
Eigen::VectorXdRefConst  goal 
)

Definition at line 176 of file bounded_end_pose_problem.cpp.

◆ SetRho()

void exotica::BoundedEndPoseProblem::SetRho ( const std::string &  task_name,
const double &  rho 
)

Definition at line 190 of file bounded_end_pose_problem.cpp.

◆ Update()

void exotica::BoundedEndPoseProblem::Update ( Eigen::VectorXdRefConst  x)

Definition at line 130 of file bounded_end_pose_problem.cpp.

Member Data Documentation

◆ cost

EndPoseTask exotica::BoundedEndPoseProblem::cost

Definition at line 63 of file bounded_end_pose_problem.h.

◆ hessian

Hessian exotica::BoundedEndPoseProblem::hessian

Definition at line 67 of file bounded_end_pose_problem.h.

◆ jacobian

Eigen::MatrixXd exotica::BoundedEndPoseProblem::jacobian

Definition at line 68 of file bounded_end_pose_problem.h.

◆ length_jacobian

int exotica::BoundedEndPoseProblem::length_jacobian

Definition at line 71 of file bounded_end_pose_problem.h.

◆ length_Phi

int exotica::BoundedEndPoseProblem::length_Phi

Definition at line 70 of file bounded_end_pose_problem.h.

◆ num_tasks

int exotica::BoundedEndPoseProblem::num_tasks

Definition at line 72 of file bounded_end_pose_problem.h.

◆ Phi

TaskSpaceVector exotica::BoundedEndPoseProblem::Phi

Definition at line 66 of file bounded_end_pose_problem.h.

◆ W

Eigen::MatrixXd exotica::BoundedEndPoseProblem::W

Definition at line 65 of file bounded_end_pose_problem.h.


The documentation for this class was generated from the following files:


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Oct 20 2023 02:59:49