include
jsk_footstep_planner
simple_neighbored_graph.h
Go to the documentation of this file.
1
// -*- mode: c++ -*-
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2015, JSK Lab
6
* All rights reserved.
7
*
8
* Redistribution and use in source and binary forms, with or without
9
* modification, are permitted provided that the following conditions
10
* are met:
11
*
12
* * Redistributions of source code must retain the above copyright
13
* notice, this list of conditions and the following disclaimer.
14
* * Redistributions in binary form must reproduce the above
15
* copyright notice, this list of conditions and the following
16
* disclaimer in the documentation and/o2r other materials provided
17
* with the distribution.
18
* * Neither the name of the JSK Lab nor the names of its
19
* contributors may be used to endorse or promote products derived
20
* from this software without specific prior written permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*********************************************************************/
35
36
37
#ifndef JSK_FOOTSTEP_PLANNER_SIMPLE_NEIGHBORED_GRAPH_
38
#define JSK_FOOTSTEP_PLANNER_SIMPLE_NEIGHBORED_GRAPH_
39
40
#include <string>
41
#include "
jsk_footstep_planner/graph.h
"
42
43
namespace
jsk_footstep_planner
44
{
45
class
SimpleNeighboredNode
46
{
47
public
:
48
typedef
boost::shared_ptr<SimpleNeighboredNode>
Ptr
;
49
50
SimpleNeighboredNode
(
const
std::string& name):
name_
(
name
)
51
{
52
53
}
54
55
virtual
void
addNeighbor
(
SimpleNeighboredNode::Ptr
node)
56
{
57
neighbors_
.push_back(node);
58
}
59
60
virtual
61
std::vector<SimpleNeighboredNode::Ptr>
62
getNeighbors
()
63
{
64
return
neighbors_
;
65
}
66
67
virtual
std::string
getName
() {
return
name_
; }
68
bool
operator==
(
SimpleNeighboredNode
& other)
69
{
70
return
name_
== other.getName();
71
}
72
73
protected
:
74
std::string
name_
;
75
std::vector<SimpleNeighboredNode::Ptr>
neighbors_
;
76
private
:
77
78
};
79
80
class
SimpleNeighboredGraph
:
public
Graph
<SimpleNeighboredNode>
81
{
82
public
:
83
typedef
boost::shared_ptr<SimpleNeighboredGraph>
Ptr
;
84
85
SimpleNeighboredGraph
() {}
86
virtual
std::vector<SimpleNeighboredGraph::StatePtr>
successors
(
87
StatePtr
target_state)
88
{
89
return
target_state->getNeighbors();
90
}
91
92
virtual
double
pathCost
(
StatePtr
from,
StatePtr
to,
double
prev_cost)
93
{
94
return
prev_cost + 1;
95
}
96
97
virtual
bool
isGoal
(
StatePtr
state)
98
{
99
return
*
goal_state_
== *
state
;
100
}
101
102
virtual
StatePtr
103
findNode
(
const
std::string& name)
104
{
105
for
(
size_t
i = 0;
i
<
nodes_
.size();
i
++) {
106
StatePtr
s
=
nodes_
[
i
];
107
if
(
s
->getName() == name) {
108
return
s
;
109
}
110
}
111
return
StatePtr
();
112
}
113
114
protected
:
115
private
:
116
117
};
118
}
119
120
#endif
jsk_footstep_planner::SimpleNeighboredNode::operator==
bool operator==(SimpleNeighboredNode &other)
Definition:
simple_neighbored_graph.h:132
boost::shared_ptr
i
int i
jsk_footstep_planner::Graph< SimpleNeighboredNode >::goal_state_
StatePtr goal_state_
Definition:
graph.h:135
jsk_footstep_planner::SimpleNeighboredGraph::Ptr
boost::shared_ptr< SimpleNeighboredGraph > Ptr
Definition:
simple_neighbored_graph.h:115
jsk_footstep_planner::SimpleNeighboredGraph
Definition:
simple_neighbored_graph.h:112
jsk_footstep_planner::SimpleNeighboredGraph::isGoal
virtual bool isGoal(StatePtr state)
Definition:
simple_neighbored_graph.h:129
jsk_footstep_planner::Graph
Definition:
graph.h:78
jsk_footstep_planner::SimpleNeighboredNode::name_
std::string name_
Definition:
simple_neighbored_graph.h:138
jsk_footstep_planner::SimpleNeighboredGraph::findNode
virtual StatePtr findNode(const std::string &name)
Definition:
simple_neighbored_graph.h:135
jsk_footstep_planner
Definition:
ann_grid.h:50
jsk_footstep_planner::SimpleNeighboredGraph::SimpleNeighboredGraph
SimpleNeighboredGraph()
Definition:
simple_neighbored_graph.h:117
jsk_footstep_planner::SimpleNeighboredNode::Ptr
boost::shared_ptr< SimpleNeighboredNode > Ptr
Definition:
simple_neighbored_graph.h:112
name
std::string name
jsk_footstep_planner::SimpleNeighboredGraph::successors
virtual std::vector< SimpleNeighboredGraph::StatePtr > successors(StatePtr target_state)
Definition:
simple_neighbored_graph.h:118
jsk_footstep_planner::SimpleNeighboredNode::neighbors_
std::vector< SimpleNeighboredNode::Ptr > neighbors_
Definition:
simple_neighbored_graph.h:139
jsk_footstep_planner::Graph< SimpleNeighboredNode >::StatePtr
boost::shared_ptr< StateT > StatePtr
Definition:
graph.h:115
jsk_footstep_planner::SimpleNeighboredGraph::pathCost
virtual double pathCost(StatePtr from, StatePtr to, double prev_cost)
Definition:
simple_neighbored_graph.h:124
state
state
jsk_footstep_planner::SimpleNeighboredNode::addNeighbor
virtual void addNeighbor(SimpleNeighboredNode::Ptr node)
Definition:
simple_neighbored_graph.h:119
graph.h
jsk_footstep_planner::SimpleNeighboredNode::SimpleNeighboredNode
SimpleNeighboredNode(const std::string &name)
Definition:
simple_neighbored_graph.h:114
pose_array.s
s
Definition:
pose_array.py:22
jsk_footstep_planner::SimpleNeighboredNode::getNeighbors
virtual std::vector< SimpleNeighboredNode::Ptr > getNeighbors()
Definition:
simple_neighbored_graph.h:126
jsk_footstep_planner::Graph< SimpleNeighboredNode >::nodes_
std::vector< StatePtr > nodes_
Definition:
graph.h:136
jsk_footstep_planner::SimpleNeighboredNode::getName
virtual std::string getName()
Definition:
simple_neighbored_graph.h:131
jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Jan 24 2024 04:05:30