Public Types | Public Member Functions | Protected Attributes | List of all members
RTreeContext Class Reference

#include <rtree_planner_context.h>

+ Inheritance diagram for RTreeContext:
+ Collaboration diagram for RTreeContext:

Public Types

typedef std::pair< index, indexedge
 
typedef std::size_t index
 
typedef std::vector< indexpath
 
typedef boost::array< double, 6 > vertex
 

Public Member Functions

virtual void clear ()
 
bool edge_collides (const vertex &qA, const vertex &qB, double step=0.01) const
 
std::vector< edgemake_edges (const std::vector< vertex > &V) const
 
std::vector< vertexmake_vertices (int N) const
 
template<typename Container >
void make_vertices (Container &nRandomPos, std::size_t N)
 
 RTreeContext (const robot_model::RobotModelConstPtr &model, const std::string &name, const std::string &group, const ros::NodeHandle &nh=ros::NodeHandle("~"))
 
index search_accessibility (const std::vector< vertex > &V, const vertex &q) const
 
index search_departability (const std::vector< vertex > &V, const vertex &q) const
 
path search_path (const std::vector< vertex > &V, const std::vector< edge > &E, index access_idx, index depart_idx) const
 
virtual bool solve (planning_interface::MotionPlanResponse &res)
 
virtual bool solve (planning_interface::MotionPlanDetailedResponse &res)
 
bool state_collides (const vertex &q) const
 
virtual bool terminate ()
 
virtual ~RTreeContext ()
 

Protected Attributes

robot_model::RobotModelConstPtr robotmodel
 

Detailed Description

Definition at line 58 of file rtree_planner_context.h.

Member Typedef Documentation

§ edge

typedef std::pair<index,index> RTreeContext::edge

Definition at line 64 of file rtree_planner_context.h.

§ index

typedef std::size_t RTreeContext::index

Definition at line 63 of file rtree_planner_context.h.

§ path

typedef std::vector<index> RTreeContext::path

Definition at line 65 of file rtree_planner_context.h.

§ vertex

typedef boost::array<double,6> RTreeContext::vertex

Definition at line 62 of file rtree_planner_context.h.

Constructor & Destructor Documentation

§ RTreeContext()

RTreeContext::RTreeContext ( const robot_model::RobotModelConstPtr &  model,
const std::string &  name,
const std::string &  group,
const ros::NodeHandle &  nh = ros::NodeHandle("~") 
)

Definition at line 73 of file rtree_planner_context.cpp.

§ ~RTreeContext()

RTreeContext::~RTreeContext ( )
virtual

Definition at line 80 of file rtree_planner_context.cpp.

Member Function Documentation

§ clear()

void RTreeContext::clear ( )
virtual

Definition at line 417 of file rtree_planner_context.cpp.

§ edge_collides()

bool RTreeContext::edge_collides ( const vertex qA,
const vertex qB,
double  step = 0.01 
) const

Feel free to change this method if you can do better.

Test if a linear trajectory between two states collides with the environment. Call this method if you need to find if the robot collides with the environment if it moves linearly between two states.

Parameters
[in]qAThe start robot state
[in]qBThe final robot state
stepThe joint step used in between configurations
Returns
true if the robot trajectory collides. false otherwise

Definition at line 95 of file rtree_planner_context.cpp.

§ make_edges()

std::vector< RTreeContext::edge > RTreeContext::make_edges ( const std::vector< vertex > &  V) const

TODO

Create a vector of edges. Each vertex represent a pair of vertex indices. For example, the pair (1,10) connects the vertices V[1] to V[10]. There is no restriction on how many edges your graph requires.

Parameters
[in]VA vector of N collision-free configurations
Returns
A vector of collision-free edges

Definition at line 125 of file rtree_planner_context.cpp.

§ make_vertices() [1/2]

std::vector< RTreeContext::vertex > RTreeContext::make_vertices ( int  N) const

TODO

Create a vector of N vertices. Each vertex represent a collision-free configuration (i.e. 6 joints) of the robot.

Parameters
NThe number of vertices in the graph
Returns
A vector of N collision-free configurations

Definition at line 108 of file rtree_planner_context.cpp.

§ make_vertices() [2/2]

template<typename Container >
void RTreeContext::make_vertices ( Container &  nRandomPos,
std::size_t  N 
)

Definition at line 176 of file rtree_planner_context.cpp.

§ search_accessibility()

RTreeContext::index RTreeContext::search_accessibility ( const std::vector< vertex > &  V,
const vertex q 
) const

TODO

Search for a vertex that is accessible from a start configuration with a collision-free trajectory. The method returns the index of the accessible vertex.

Parameters
[in]VA vector of N collision-free configurations
[in]qThe start configuration
Returns
The index of the accessible vertex

Definition at line 138 of file rtree_planner_context.cpp.

§ search_departability()

RTreeContext::index RTreeContext::search_departability ( const std::vector< vertex > &  V,
const vertex q 
) const

TODO

Search for a vertex that is "departable" to a final configuration with a collision-free trajectory. The method returns the index of the departable vertex.

Parameters
[in]VA vector of N collision-free configurations
[in]qThe final configuration
Returns
The index of the departable vertex

Definition at line 149 of file rtree_planner_context.cpp.

§ search_path()

RTreeContext::path RTreeContext::search_path ( const std::vector< vertex > &  V,
const std::vector< edge > &  E,
RTreeContext::index  idx_start,
RTreeContext::index  idx_final 
) const

TODO

Search the graph (V,E) for a path between two vertices. collision-free trajectory. The method returns the index of the departable vertex.

Parameters
[in]VA vector of N collision-free configurations
[in]EA vector of collision-free edges
[in]access_idxThe index of the accessible vertex
[in]depart_idxThe index of the departable vertex
Returns
A vector representing a sequence of vertices

Definition at line 161 of file rtree_planner_context.cpp.

§ solve() [1/2]

bool RTreeContext::solve ( planning_interface::MotionPlanResponse &  res)
virtual

Definition at line 235 of file rtree_planner_context.cpp.

§ solve() [2/2]

bool RTreeContext::solve ( planning_interface::MotionPlanDetailedResponse &  res)
virtual

Definition at line 414 of file rtree_planner_context.cpp.

§ state_collides()

bool RTreeContext::state_collides ( const vertex q) const

Feel free to change this method if you can do better.

Test if a state collides with the scene. Call this method if you need to find if the robot collides with the environment in the given robot's state.

Parameters
[in]qThe robot state
Returns
true if the robot state collides. false otherwise

Definition at line 82 of file rtree_planner_context.cpp.

§ terminate()

bool RTreeContext::terminate ( )
virtual

Definition at line 419 of file rtree_planner_context.cpp.

Member Data Documentation

§ robotmodel

robot_model::RobotModelConstPtr RTreeContext::robotmodel
protected

Definition at line 173 of file rtree_planner_context.h.


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