Public Member Functions | Protected Member Functions | Protected Attributes
descartes_planner::DensePlanner Class Reference

#include <dense_planner.h>

Inheritance diagram for descartes_planner::DensePlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool addAfter (const descartes_core::TrajectoryPt::ID &ref_id, descartes_core::TrajectoryPtPtr tp)
virtual bool addBefore (const descartes_core::TrajectoryPt::ID &ref_id, descartes_core::TrajectoryPtPtr tp)
 DensePlanner ()
virtual void getConfig (descartes_core::PlannerConfig &config) const
virtual int getErrorCode () const
virtual bool getErrorMessage (int error_code, std::string &msg) const
virtual bool getPath (std::vector< descartes_core::TrajectoryPtPtr > &path) const
const PlanningGraphgetPlanningGraph () const
virtual bool initialize (descartes_core::RobotModelConstPtr model)
virtual bool initialize (descartes_core::RobotModelConstPtr model, descartes_planner::CostFunction cost_function_callback)
virtual bool modify (const descartes_core::TrajectoryPt::ID &ref_id, descartes_core::TrajectoryPtPtr tp)
virtual bool planPath (const std::vector< descartes_core::TrajectoryPtPtr > &traj)
virtual bool remove (const descartes_core::TrajectoryPt::ID &ref_id)
virtual bool setConfig (const descartes_core::PlannerConfig &config)
virtual ~DensePlanner ()

Protected Member Functions

descartes_core::TrajectoryPtPtr get (const descartes_core::TrajectoryPt::ID &ref_id)
descartes_core::TrajectoryPt::ID getNext (const descartes_core::TrajectoryPt::ID &ref_id)
descartes_core::TrajectoryPt::ID getPrevious (const descartes_core::TrajectoryPt::ID &ref_id)
bool updatePath ()

Protected Attributes

descartes_core::PlannerConfig config_
int error_code_
std::map< int, std::string > error_map_
std::vector
< descartes_core::TrajectoryPtPtr > 
path_
boost::shared_ptr
< descartes_planner::PlanningGraph
planning_graph_

Detailed Description

Definition at line 16 of file dense_planner.h.


Constructor & Destructor Documentation

Definition at line 13 of file src/dense_planner.cpp.

Definition at line 23 of file src/dense_planner.cpp.


Member Function Documentation

bool descartes_planner::DensePlanner::addAfter ( const descartes_core::TrajectoryPt::ID ref_id,
descartes_core::TrajectoryPtPtr  tp 
) [virtual]

Definition at line 227 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::addBefore ( const descartes_core::TrajectoryPt::ID ref_id,
descartes_core::TrajectoryPtPtr  tp 
) [virtual]

Definition at line 263 of file src/dense_planner.cpp.

descartes_core::TrajectoryPtPtr descartes_planner::DensePlanner::get ( const descartes_core::TrajectoryPt::ID ref_id) [protected]

Definition at line 174 of file src/dense_planner.cpp.

Implements descartes_core::PathPlannerBase.

Definition at line 51 of file src/dense_planner.cpp.

Implements descartes_core::PathPlannerBase.

Definition at line 372 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::getErrorMessage ( int  error_code,
std::string &  msg 
) const [virtual]

Implements descartes_core::PathPlannerBase.

Definition at line 377 of file src/dense_planner.cpp.

Definition at line 153 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::getPath ( std::vector< descartes_core::TrajectoryPtPtr > &  path) const [virtual]

Definition at line 218 of file src/dense_planner.cpp.

Definition at line 39 of file dense_planner.h.

Definition at line 56 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::initialize ( descartes_core::RobotModelConstPtr  model) [virtual]

Definition at line 27 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::initialize ( descartes_core::RobotModelConstPtr  model,
descartes_planner::CostFunction  cost_function_callback 
) [virtual]

Definition at line 35 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::modify ( const descartes_core::TrajectoryPt::ID ref_id,
descartes_core::TrajectoryPtPtr  tp 
) [virtual]

Definition at line 336 of file src/dense_planner.cpp.

bool descartes_planner::DensePlanner::planPath ( const std::vector< descartes_core::TrajectoryPtPtr > &  traj) [virtual]

Definition at line 194 of file src/dense_planner.cpp.

Implements descartes_core::PathPlannerBase.

Definition at line 299 of file src/dense_planner.cpp.

Implements descartes_core::PathPlannerBase.

Definition at line 44 of file src/dense_planner.cpp.

Definition at line 78 of file src/dense_planner.cpp.


Member Data Documentation

Definition at line 53 of file dense_planner.h.

Definition at line 52 of file dense_planner.h.

std::map<int, std::string> descartes_planner::DensePlanner::error_map_ [protected]

Definition at line 55 of file dense_planner.h.

std::vector<descartes_core::TrajectoryPtPtr> descartes_planner::DensePlanner::path_ [protected]

Definition at line 54 of file dense_planner.h.

Definition at line 51 of file dense_planner.h.


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


descartes_planner
Author(s): Jorge Nicho
autogenerated on Thu Jun 6 2019 21:36:12