Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
descartes_planner::PlanningGraph Class Reference

#include <planning_graph.h>

List of all members.

Public Member Functions

bool addTrajectory (descartes_core::TrajectoryPtPtr point, descartes_core::TrajectoryPt::ID previous_id, descartes_core::TrajectoryPt::ID next_id)
 adds a single trajectory point to the graph
void clear ()
 Clear all previous graph data.
bool findEndVertices (std::vector< JointGraph::vertex_descriptor > &end_points) const
 simple function to iterate over all graph vertices to find ones that do not have an outgoing edge
bool findStartVertices (std::vector< JointGraph::vertex_descriptor > &start_points) const
 simple function to iterate over all graph vertices to find ones that do not have an incoming edge
CartesianMap getCartesianMap () const
bool getCartesianTrajectory (std::vector< descartes_core::TrajectoryPtPtr > &traj)
const JointGraphgetGraph () const
const JointMapgetJointMap () const
descartes_core::RobotModelConstPtr getRobotModel ()
bool getShortestPath (double &cost, std::list< descartes_trajectory::JointTrajectoryPt > &path)
 Calculate and return the shortest path from the given joint solution indices.
bool insertGraph (const std::vector< descartes_core::TrajectoryPtPtr > *points)
 initial population of graph trajectory elements
bool modifyTrajectory (descartes_core::TrajectoryPtPtr point)
 PlanningGraph (descartes_core::RobotModelConstPtr model)
 PlanningGraph (descartes_core::RobotModelConstPtr model, CostFunction cost_function_callback)
void printGraph ()
 Utility function for printing the graph to the console NOTE: should add other formats for output.
void printMaps ()
bool removeTrajectory (descartes_core::TrajectoryPtPtr point)
virtual ~PlanningGraph ()

Protected Types

typedef std::pair< bool, double > EdgeWeightResult
 A pair indicating the validity of the edge, and if valid, the cost associated with that edge.

Protected Member Functions

bool calculateAllEdgeWeights (const std::vector< std::vector< descartes_trajectory::JointTrajectoryPt >> &poses, std::vector< JointEdge > &edges)
 (Re)populate the edge list for the graph from the list of joint solutions
bool calculateEdgeWeights (const std::vector< descartes_core::TrajectoryPt::ID > &start_joints, const std::vector< descartes_core::TrajectoryPt::ID > &end_joints, std::vector< JointEdge > &edge_results)
 calculate weights fro each start point to each end point
bool calculateEdgeWeights (const std::vector< descartes_trajectory::JointTrajectoryPt > &start_joints, const std::vector< descartes_trajectory::JointTrajectoryPt > &end_joints, std::vector< JointEdge > &edge_results) const
bool calculateJointSolutions (const std::vector< descartes_core::TrajectoryPtPtr > &points, std::vector< std::vector< descartes_trajectory::JointTrajectoryPt >> &poses)
 (Re)create the list of joint solutions from the given descartes_core::TrajectoryPt list
EdgeWeightResult edgeWeight (const descartes_trajectory::JointTrajectoryPt &start, const descartes_trajectory::JointTrajectoryPt &end) const
 function for computing edge weight based on specified cost function
bool populateGraphEdges (const std::vector< JointEdge > &edges)
 (Re)create the actual graph structure from the list of transition costs (edges)
bool populateGraphVertices (const std::vector< descartes_core::TrajectoryPtPtr > &points, std::vector< std::vector< descartes_trajectory::JointTrajectoryPt >> &poses)
 (Re)create the actual graph nodes(vertices) from the list of joint solutions (vertices)
int recalculateJointSolutionsVertexMap (std::map< descartes_core::TrajectoryPt::ID, JointGraph::vertex_descriptor > &joint_vertex_map) const

Protected Attributes

CartesianMapcartesian_point_link_
CostFunction custom_cost_function_
JointGraph dg_
JointMap joint_solutions_map_
descartes_core::RobotModelConstPtr robot_model_

Detailed Description

Definition at line 82 of file planning_graph.h.


Member Typedef Documentation

typedef std::pair<bool, double> descartes_planner::PlanningGraph::EdgeWeightResult [protected]

A pair indicating the validity of the edge, and if valid, the cost associated with that edge.

Definition at line 162 of file planning_graph.h.


Constructor & Destructor Documentation

descartes_planner::PlanningGraph::PlanningGraph ( descartes_core::RobotModelConstPtr  model)
descartes_planner::PlanningGraph::PlanningGraph ( descartes_core::RobotModelConstPtr  model,
CostFunction  cost_function_callback 
)

Definition at line 52 of file planning_graph.cpp.


Member Function Documentation

bool descartes_planner::PlanningGraph::addTrajectory ( descartes_core::TrajectoryPtPtr  point,
descartes_core::TrajectoryPt::ID  previous_id,
descartes_core::TrajectoryPt::ID  next_id 
)

adds a single trajectory point to the graph

Parameters:
pointThe new point to add to the graph
Returns:
True if the point was successfully added

Definition at line 173 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::calculateAllEdgeWeights ( const std::vector< std::vector< descartes_trajectory::JointTrajectoryPt >> &  poses,
std::vector< JointEdge > &  edges 
) [protected]

(Re)populate the edge list for the graph from the list of joint solutions

Definition at line 838 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::calculateEdgeWeights ( const std::vector< descartes_core::TrajectoryPt::ID > &  start_joints,
const std::vector< descartes_core::TrajectoryPt::ID > &  end_joints,
std::vector< JointEdge > &  edge_results 
) [protected]

calculate weights fro each start point to each end point

bool descartes_planner::PlanningGraph::calculateEdgeWeights ( const std::vector< descartes_trajectory::JointTrajectoryPt > &  start_joints,
const std::vector< descartes_trajectory::JointTrajectoryPt > &  end_joints,
std::vector< JointEdge > &  edge_results 
) const [protected]

Definition at line 907 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::calculateJointSolutions ( const std::vector< descartes_core::TrajectoryPtPtr > &  points,
std::vector< std::vector< descartes_trajectory::JointTrajectoryPt >> &  poses 
) [protected]

(Re)create the list of joint solutions from the given descartes_core::TrajectoryPt list

Definition at line 812 of file planning_graph.cpp.

Clear all previous graph data.

Definition at line 57 of file planning_graph.cpp.

function for computing edge weight based on specified cost function

Definition at line 1017 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::findEndVertices ( std::vector< JointGraph::vertex_descriptor > &  end_points) const

simple function to iterate over all graph vertices to find ones that do not have an outgoing edge

Definition at line 606 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::findStartVertices ( std::vector< JointGraph::vertex_descriptor > &  start_points) const

simple function to iterate over all graph vertices to find ones that do not have an incoming edge

Definition at line 567 of file planning_graph.cpp.

Definition at line 64 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::getCartesianTrajectory ( std::vector< descartes_core::TrajectoryPtPtr > &  traj)

Definition at line 79 of file planning_graph.cpp.

Definition at line 74 of file planning_graph.cpp.

descartes_core::RobotModelConstPtr descartes_planner::PlanningGraph::getRobotModel ( )

Definition at line 84 of file planning_graph.cpp.

Calculate and return the shortest path from the given joint solution indices.

Parameters:
startIndexThe index of the joint solution at which to start
endIndexThe index of the joint solution at which to end
costThe cost of the returned path
pathThe sequence of points (joint solutions) for the path (TODO: change to JointTrajectoryPt?)
Returns:
True if a valid path is found

Definition at line 645 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::insertGraph ( const std::vector< descartes_core::TrajectoryPtPtr > *  points)

initial population of graph trajectory elements

Parameters:
pointslist of trajectory points to be used to construct the graph
Returns:
True if the graph was successfully created

Definition at line 89 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::modifyTrajectory ( descartes_core::TrajectoryPtPtr  point)

Definition at line 301 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::populateGraphEdges ( const std::vector< JointEdge > &  edges) [protected]

(Re)create the actual graph structure from the list of transition costs (edges)

Definition at line 989 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::populateGraphVertices ( const std::vector< descartes_core::TrajectoryPtPtr > &  points,
std::vector< std::vector< descartes_trajectory::JointTrajectoryPt >> &  poses 
) [protected]

(Re)create the actual graph nodes(vertices) from the list of joint solutions (vertices)

Definition at line 944 of file planning_graph.cpp.

Utility function for printing the graph to the console NOTE: should add other formats for output.

Definition at line 753 of file planning_graph.cpp.

Definition at line 729 of file planning_graph.cpp.

int descartes_planner::PlanningGraph::recalculateJointSolutionsVertexMap ( std::map< descartes_core::TrajectoryPt::ID, JointGraph::vertex_descriptor > &  joint_vertex_map) const [protected]

Definition at line 741 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::removeTrajectory ( descartes_core::TrajectoryPtPtr  point)

Definition at line 453 of file planning_graph.cpp.


Member Data Documentation

Definition at line 173 of file planning_graph.h.

Definition at line 151 of file planning_graph.h.

Definition at line 153 of file planning_graph.h.

Definition at line 177 of file planning_graph.h.

descartes_core::RobotModelConstPtr descartes_planner::PlanningGraph::robot_model_ [protected]

Definition at line 149 of file planning_graph.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