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
CartesianMap getCartesianMap ()
bool getCartesianTrajectory (std::vector< descartes_core::TrajectoryPtPtr > &traj)
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)
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 > LinearWeightResult
 A pair indicating the validity of the edge, and if valid, the cost associated with that edge.

Protected Member Functions

bool calculateAllEdgeWeights (std::list< JointEdge > &edges)
 (Re)populate the edge list for the graph from the list of joint solutions
bool calculateEdgeWeights (const std::list< descartes_core::TrajectoryPt::ID > &start_joints, const std::list< descartes_core::TrajectoryPt::ID > &end_joints, std::list< JointEdge > &edge_results)
 calculate weights fro each start point to each end point
bool calculateJointSolutions ()
 (Re)create the list of joint solutions from the given descartes_core::TrajectoryPt list
bool findEndVertices (std::list< JointGraph::vertex_descriptor > &end_points)
 simple function to iterate over all graph vertices to find ones that do not have an outgoing edge
bool findStartVertices (std::list< JointGraph::vertex_descriptor > &start_points)
 simple function to iterate over all graph vertices to find ones that do not have an incoming edge
LinearWeightResult linearWeight (const descartes_trajectory::JointTrajectoryPt &start, const descartes_trajectory::JointTrajectoryPt &end) const
 simple function for getting edge weights based on linear vector differences
bool populateGraphEdges (const std::list< JointEdge > &edges)
 (Re)create the actual graph structure from the list of transition costs (edges)
bool populateGraphVertices ()
 (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)

Protected Attributes

std::map
< descartes_core::TrajectoryPt::ID,
CartesianPointInformation > * 
cartesian_point_link_
JointGraph dg_
std::map
< descartes_core::TrajectoryPt::ID,
descartes_trajectory::JointTrajectoryPt
joint_solutions_map_
descartes_core::RobotModelConstPtr robot_model_

Detailed Description

Definition at line 78 of file planning_graph.h.


Member Typedef Documentation

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

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

Definition at line 137 of file planning_graph.h.


Constructor & Destructor Documentation

descartes_planner::PlanningGraph::PlanningGraph ( descartes_core::RobotModelConstPtr  model)

Definition at line 44 of file planning_graph.cpp.

Definition at line 49 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 176 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::calculateAllEdgeWeights ( std::list< JointEdge > &  edges) [protected]

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

Definition at line 847 of file planning_graph.cpp.

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

calculate weights fro each start point to each end point

Definition at line 898 of file planning_graph.cpp.

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

Definition at line 804 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::findEndVertices ( std::list< JointGraph::vertex_descriptor > &  end_points) [protected]

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

Definition at line 602 of file planning_graph.cpp.

bool descartes_planner::PlanningGraph::findStartVertices ( std::list< JointGraph::vertex_descriptor > &  start_points) [protected]

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

Definition at line 562 of file planning_graph.cpp.

Definition at line 54 of file planning_graph.cpp.

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

Definition at line 81 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 643 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 86 of file planning_graph.cpp.

simple function for getting edge weights based on linear vector differences

Definition at line 993 of file planning_graph.cpp.

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

Definition at line 304 of file planning_graph.cpp.

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

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

Definition at line 965 of file planning_graph.cpp.

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

Definition at line 946 of file planning_graph.cpp.

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

Definition at line 746 of file planning_graph.cpp.

Definition at line 722 of file planning_graph.cpp.

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

Definition at line 734 of file planning_graph.cpp.

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

Definition at line 451 of file planning_graph.cpp.


Member Data Documentation

Definition at line 147 of file planning_graph.h.

Definition at line 129 of file planning_graph.h.

Definition at line 151 of file planning_graph.h.

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

Definition at line 127 of file planning_graph.h.


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


descartes_planner
Author(s): Jorge Nicho
autogenerated on Wed Aug 26 2015 11:21:35