GCC Code Coverage Report


Directory: ./
File: include/hpp/manipulation/graph/state.hh
Date: 2025-03-07 11:10:46
Exec Total Coverage
Lines: 9 14 64.3%
Branches: 0 0 -%

Line Branch Exec Source
1 // Copyright (c) 2014, LAAS-CNRS
2 // Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
3 //
4
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // 1. Redistributions of source code must retain the above copyright
10 // notice, this list of conditions and the following disclaimer.
11 //
12 // 2. Redistributions in binary form must reproduce the above copyright
13 // notice, this list of conditions and the following disclaimer in the
14 // documentation and/or other materials provided with the distribution.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
19 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
20 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
21 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
22 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
24 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
27 // DAMAGE.
28
29 #ifndef HPP_MANIPULATION_GRAPH_STATE_HH
30 #define HPP_MANIPULATION_GRAPH_STATE_HH
31
32 #include <functional>
33 #include <hpp/constraints/implicit.hh>
34 #include <hpp/core/config-projector.hh>
35 #include <hpp/core/constraint-set.hh>
36
37 #include "hpp/manipulation/config.hh"
38 #include "hpp/manipulation/fwd.hh"
39 #include "hpp/manipulation/graph/edge.hh"
40 #include "hpp/manipulation/graph/fwd.hh"
41 #include "hpp/manipulation/graph/graph-component.hh"
42
43 namespace hpp {
44 namespace manipulation {
45 using constraints::Implicit;
46 using constraints::ImplicitPtr_t;
47 namespace graph {
48 /// \addtogroup constraint_graph
49 /// \{
50
51 /// State of an end-effector.
52 ///
53 /// States of the graph of constraints. There is one
54 /// graph for each end-effector.
55 class HPP_MANIPULATION_DLLAPI State : public GraphComponent {
56 public:
57 typedef std::function<EdgePtr_t(const std::string&, const GraphWkPtr_t&,
58 const StateWkPtr_t&, const StateWkPtr_t&)>
59 EdgeFactory;
60 /// Destructor
61 ~State();
62
63 /// Create a new state.
64 static StatePtr_t create(const std::string& name);
65
66 /// Create a link from this state to the given state.
67 /// \param w if strictly negative, the edge is not included in the neighbor
68 /// list. Otherwise, it is included with Weight_t w
69 EdgePtr_t linkTo(const std::string& name, const StatePtr_t& to,
70 16 const size_type& w = 1, EdgeFactory create = Edge::create);
71
72 /// Check whether the configuration is in this state.
73 /// \code
74 /// return configConstraint()->isSatisfied (config);
75 /// \endcode
76 /// \note You should not use this method to know in which states a
77 /// configuration is. This only checks if the configuration satisfies
78 /// the constraints. Instead, use the class StateSelector.
79 virtual bool contains(ConfigurationIn_t config) const;
80
81 inline bool isWaypoint() const { return isWaypoint_; }
82
83 4 inline void isWaypoint(bool isWaypoint) { isWaypoint_ = isWaypoint; }
84
85 /// Get the parent StateSelector.
86 StateSelectorWkPtr_t stateSelector() const { return selector_; }
87
88 /// Set the StateSelector containing this state.
89 4 void stateSelector(const StateSelectorWkPtr_t& parent) {
90 4 selector_ = parent;
91 4 };
92
93 /// Get the neighbors
94 4 const Neighbors_t& neighbors() const { return neighbors_; }
95
96 /// Get the neighbors
97 Edges_t neighborEdges() const { return neighbors_.values(); }
98
99 /// Get the hidden neighbors
100 /// It is a vector of transitions outgoing from this state and that are
101 /// included in a waypoint edge.
102 const Edges_t& hiddenNeighbors() const { return hiddenNeighbors_; }
103
104 /// Set weight of edge starting from this state.
105 void updateWeight(const EdgePtr_t& edge, const Weight_t& w);
106
107 /// Get weight of edge starting from this state.
108 Weight_t getWeight(const EdgePtr_t& edge);
109
110 /// Constraint to project onto this state.
111 1 ConstraintSetPtr_t configConstraint() const {
112 1 throwIfNotInitialized();
113 1 return configConstraints_;
114 }
115
116 /// Add constraint to the state
117 /// Call the parent implementation.
118 /// \throw std::logic_error if the constraint is parameterizable
119 /// (contains at least one Equality comparison type).
120 virtual void addNumericalConstraint(const ImplicitPtr_t& numConstraint);
121
122 /// Add a constraint for paths that lie in this state.
123 virtual void addNumericalConstraintForPath(const ImplicitPtr_t& nm) {
124 invalidate();
125 numericalConstraintsForPath_.push_back(nm);
126 }
127
128 /// Insert the numerical constraints in a ConfigProjector
129 /// \return true is at least one ImplicitPtr_t was inserted.
130 bool insertNumericalConstraintsForPath(ConfigProjectorPtr_t& proj) const {
131 for (const auto& nc : numericalConstraintsForPath_) proj->add(nc);
132 return !numericalConstraintsForPath_.empty();
133 }
134
135 /// Get a reference to the NumericalConstraints_t
136 const NumericalConstraints_t& numericalConstraintsForPath() const {
137 return numericalConstraintsForPath_;
138 }
139
140 /// Print the object in a stream.
141 std::ostream& dotPrint(std::ostream& os, dot::DrawingAttributes da =
142 dot::DrawingAttributes()) const;
143
144 protected:
145 /// Initialize the object.
146 void init(const StateWkPtr_t& self);
147
148 /// Constructor
149 State(const std::string& name);
150
151 /// Print the object in a stream.
152 std::ostream& print(std::ostream& os) const;
153
154 virtual void populateTooltip(dot::Tooltip& tp) const;
155
156 virtual void initialize();
157
158 private:
159 /// List of possible motions from this state (i.e. the outgoing
160 /// vertices).
161 Neighbors_t neighbors_;
162 Edges_t hiddenNeighbors_;
163
164 /// Set of constraints to be statisfied.
165 ConstraintSetPtr_t configConstraints_;
166
167 /// Stores the numerical constraints for path.
168 NumericalConstraints_t numericalConstraintsForPath_;
169
170 /// A selector that will implement the selection of the next state.
171 StateSelectorWkPtr_t selector_;
172
173 /// Weak pointer to itself.
174 StateWkPtr_t wkPtr_;
175
176 bool isWaypoint_;
177 }; // class State
178
179 /// \}
180 } // namespace graph
181 } // namespace manipulation
182 } // namespace hpp
183
184 #endif // HPP_MANIPULATION_GRAPH_STATE_HH
185