Skip to content
Snippets Groups Projects
Commit 8ea7add4 authored by Florent Lamiraux's avatar Florent Lamiraux
Browse files

Remove deprecated methods and fix compilation warnings.

parent 928cb76d
No related branches found
No related tags found
No related merge requests found
......@@ -81,30 +81,6 @@ class HPP_MANIPULATION_DLLAPI Edge : public GraphComponent {
static EdgePtr_t create(const std::string& name, const GraphWkPtr_t& graph,
const StateWkPtr_t& from, const StateWkPtr_t& to);
/// Generate a reachable configuration in the target state
///
/// \param nStart node containing the configuration defining the right
/// hand side of the edge constraint,
/// \param[in,out] q input configuration used to initialize the
/// numerical solver and output configuration lying
/// in the target state and reachable along the edge
/// from nnear
/// \deprecated Use generateTargetConfig instead.
virtual bool applyConstraints(core::NodePtr_t nStart, ConfigurationOut_t q)
const HPP_MANIPULATION_DEPRECATED;
/// Generate a reachable configuration in the target state
///
/// \param qStart node containing the configuration defining the right
/// hand side of the edge path constraint,
/// \param[in,out] q input configuration used to initialize the
/// numerical solver and output configuration lying
/// in the target state and reachable along the edge
/// from nnear.
/// \deprecated Use generateTargetConfig instead.
virtual bool applyConstraints(ConfigurationIn_t qStart, ConfigurationOut_t q)
const HPP_MANIPULATION_DEPRECATED;
/// Generate a reachable configuration in the target state
///
/// \param nStart node containing the configuration defining the right
......@@ -188,10 +164,6 @@ class HPP_MANIPULATION_DLLAPI Edge : public GraphComponent {
std::ostream& os,
dot::DrawingAttributes da = dot::DrawingAttributes()) const;
/// Constraint of the destination state and of the path
/// \deprecated Use targetConstraint instead
ConstraintSetPtr_t configConstraint() const HPP_MANIPULATION_DEPRECATED;
/// Constraint of the destination state and of the path
ConstraintSetPtr_t targetConstraint() const;
......@@ -210,9 +182,6 @@ class HPP_MANIPULATION_DLLAPI Edge : public GraphComponent {
/// Constructor
Edge(const std::string& name);
virtual ConstraintSetPtr_t buildConfigConstraint()
HPP_MANIPULATION_DEPRECATED;
/// Build path and target state constraint set.
virtual ConstraintSetPtr_t buildTargetConstraint();
......@@ -303,18 +272,6 @@ class HPP_MANIPULATION_DLLAPI WaypointEdge : public Edge {
virtual bool build(core::PathPtr_t& path, ConfigurationIn_t q1,
ConfigurationIn_t q2) const;
/// Generate a reachable configuration in the target state
///
/// \param qStart node containing the configuration defining the right
/// hand side of the edge path constraint,
/// \param[in,out] q input configuration used to initialize the
/// numerical solver and output configuration lying
/// in the target state and reachable along the edge
/// from nnear.
/// deprecated Used generateTargetConfig instead.
virtual bool applyConstraints(ConfigurationIn_t qStart, ConfigurationOut_t q)
const HPP_MANIPULATION_DEPRECATED;
/// Generate a reachable configuration in the target state
///
/// \param qStart node containing the configuration defining the right
......@@ -448,30 +405,6 @@ class HPP_MANIPULATION_DLLAPI LevelSetEdge : public Edge {
const StateWkPtr_t& from,
const StateWkPtr_t& to);
/// Generate a reachable configuration in the target state
///
/// \param nStart node containing the configuration defining the right
/// hand side of the edge constraint,
/// \param[in,out] q input configuration used to initialize the
/// numerical solver and output configuration lying
/// in the target state and reachable along the edge
/// from nnear
/// \deprecated Use generateTargetConfig instead.
virtual bool applyConstraints(core::NodePtr_t nStart, ConfigurationOut_t q)
const HPP_MANIPULATION_DEPRECATED;
/// Generate a reachable configuration in the target state
///
/// \param qStart node containing the configuration defining the right
/// hand side of the edge path constraint,
/// \param[in,out] q input configuration used to initialize the
/// numerical solver and output configuration lying
/// in the target state and reachable along the edge
/// from nnear.
/// \deprecated Use generateTargetConfig instead.
virtual bool applyConstraints(ConfigurationIn_t qStart, ConfigurationOut_t q)
const HPP_MANIPULATION_DEPRECATED;
/// Generate a reachable configuration in the target state
///
/// \param nStart node containing the configuration defining the right
......@@ -505,10 +438,6 @@ class HPP_MANIPULATION_DLLAPI LevelSetEdge : public Edge {
ConfigurationIn_t qLeaf,
ConfigurationOut_t q) const;
/// \deprecated Use buildTargetConstraint instead
virtual ConstraintSetPtr_t buildConfigConstraint()
HPP_MANIPULATION_DEPRECATED;
/// Build path and target state constraints
virtual ConstraintSetPtr_t buildTargetConstraint();
......
......@@ -92,10 +92,6 @@ class HPP_MANIPULATION_DLLAPI GraphComponent {
/// The component needs to be initialized again.
virtual void invalidate() { isInit_ = false; }
/// Declare a component as dirty
/// \deprecated call invalidate instead
void setDirty() HPP_MANIPULATION_DEPRECATED;
/// Set whether hierachical constraints are solved level by level
/// \sa hpp::constraints::solver::HierarchicalIterative
void solveLevelByLevel(bool solveLevelByLevel) {
......
......@@ -46,8 +46,7 @@ namespace graph {
/// Description of the constraint graph.
///
/// This class contains a graph representing a robot with several
/// end-effectors.
/// This class contains a graph representing a a manipulation problem
///
/// One must make sure not to create loop with shared pointers.
/// To ensure that, the classes are defined as follow:
......@@ -55,6 +54,10 @@ namespace graph {
/// - A StateSelector owns the Node s related to one gripper.
/// - A State owns its outgoing Edge s.
/// - An Edge does not own anything.
///
/// \note The graph and all its components have a unique index starting
/// at 0 for the graph itself. The index of a component can be retrieved
/// using method GraphComponent::id.
class HPP_MANIPULATION_DLLAPI Graph : public GraphComponent {
public:
/// Create a new Graph.
......@@ -137,11 +140,6 @@ class HPP_MANIPULATION_DLLAPI Graph : public GraphComponent {
/// \return The initialized projector.
ConstraintSetPtr_t configConstraint(const StatePtr_t& state) const;
/// Constraints of path and target state of an edge
/// \deprecated Use tagetConstraint instead.
ConstraintSetPtr_t configConstraint(const EdgePtr_t& edge) const
HPP_MANIPULATION_DEPRECATED;
/// Constraints a configuration in target state should satisfy
/// \param edge a transition
/// \return The set of constraints a configuration lying in the
......@@ -260,7 +258,7 @@ class HPP_MANIPULATION_DLLAPI Graph : public GraphComponent {
void init(const GraphWkPtr_t& weak, DevicePtr_t robot);
/// Constructor
/// \param sm a steering method to create paths from edges
/// \param problem a pointer to the problem
Graph(const std::string& name, const ProblemPtr_t& problem);
/// Print the object in a stream.
......
......@@ -203,7 +203,6 @@ class HPP_MANIPULATION_DLLLOCAL StateHistogram
/// The constraint graph
graph::GraphPtr_t graph_;
};
typedef StateHistogram NodeHistogram HPP_MANIPULATION_DEPRECATED;
typedef shared_ptr<StateHistogram> NodeHistogramPtr_t;
} // namespace graph
} // namespace manipulation
......
......@@ -72,10 +72,6 @@ class HPP_MANIPULATION_DLLAPI Roadmap : public core::Roadmap {
const ConnectedComponentPtr_t& connectedComponent,
const graph::StatePtr_t& state, value_type& minDistance) const;
/// Get graph state corresponding to given roadmap node
/// \deprecated use getState instead
graph::StatePtr_t getNode(RoadmapNodePtr_t node) HPP_MANIPULATION_DEPRECATED;
/// Update the graph of connected components after new connection
/// \param cc1, cc2 the two connected components that have just been
/// connected.
......
......@@ -92,7 +92,7 @@ void ConnectedComponent::merge(const core::ConnectedComponentPtr_t& otherCC) {
void ConnectedComponent::addNode(const core::NodePtr_t& node) {
core::ConnectedComponent::addNode(node);
// Find right graph state in map and add roadmap node to corresponding vector
const RoadmapNodePtr_t& n = static_cast<const RoadmapNodePtr_t>(node);
const RoadmapNodePtr_t& n = static_cast<RoadmapNodePtr_t>(node);
RoadmapPtr_t roadmap = roadmap_.lock();
if (!roadmap)
throw std::logic_error(
......
......@@ -192,11 +192,6 @@ ConstraintSetPtr_t Edge::targetConstraint() const {
return targetConstraints_;
}
ConstraintSetPtr_t Edge::configConstraint() const {
throwIfNotInitialized();
return targetConstraints_;
}
// Merge constraints of several graph components into a config projector
// Replace constraints and complement by combination of both when
// necessary.
......@@ -244,10 +239,6 @@ static void mergeConstraintsIntoConfigProjector(
for (const auto& _nc : nc) proj->add(_nc, 1);
}
ConstraintSetPtr_t Edge::buildConfigConstraint() {
return buildTargetConstraint();
}
ConstraintSetPtr_t Edge::buildTargetConstraint() {
std::string n = "(" + name() + ")";
GraphPtr_t g = graph_.lock();
......@@ -366,16 +357,6 @@ bool Edge::build(core::PathPtr_t& path, ConfigurationIn_t q1,
}
}
bool Edge::applyConstraints(core::NodePtr_t nStart,
ConfigurationOut_t q) const {
return generateTargetConfig(*(nStart->configuration()), q);
}
bool Edge::applyConstraints(ConfigurationIn_t qoffset,
ConfigurationOut_t q) const {
return generateTargetConfig(qoffset, q);
}
bool Edge::generateTargetConfig(core::NodePtr_t nStart,
ConfigurationOut_t q) const {
return generateTargetConfig(*(nStart->configuration()), q);
......@@ -489,11 +470,6 @@ bool WaypointEdge::build(core::PathPtr_t& path, ConfigurationIn_t q1,
return true;
}
bool WaypointEdge::applyConstraints(ConfigurationIn_t qStart,
ConfigurationOut_t q) const {
return generateTargetConfig(qStart, q);
}
bool WaypointEdge::generateTargetConfig(ConfigurationIn_t qStart,
ConfigurationOut_t q) const {
assert(configs_.cols() == size_type(edges_.size() + 1));
......@@ -592,11 +568,6 @@ void LevelSetEdge::populateTooltip(dot::Tooltip& tp) const {
}
}
bool LevelSetEdge::applyConstraints(ConfigurationIn_t qStart,
ConfigurationOut_t q) const {
return generateTargetConfig(qStart, q);
}
bool LevelSetEdge::generateTargetConfig(ConfigurationIn_t qStart,
ConfigurationOut_t q) const {
// First, get an offset from the histogram
......@@ -611,11 +582,6 @@ bool LevelSetEdge::generateTargetConfig(ConfigurationIn_t qStart,
return generateTargetConfigOnLeaf(qStart, qLeaf, q);
}
bool LevelSetEdge::applyConstraints(core::NodePtr_t nStart,
ConfigurationOut_t q) const {
return generateTargetConfig(nStart, q);
}
bool LevelSetEdge::generateTargetConfig(core::NodePtr_t nStart,
ConfigurationOut_t q) const {
// First, get an offset from the histogram that is not in the same connected
......@@ -738,10 +704,6 @@ void LevelSetEdge::initialize() {
}
}
ConstraintSetPtr_t LevelSetEdge::buildConfigConstraint() {
return buildTargetConstraint();
}
ConstraintSetPtr_t LevelSetEdge::buildTargetConstraint() {
std::string n = "(" + name() + ")";
GraphPtr_t g = graph_.lock();
......
......@@ -52,8 +52,6 @@ std::ostream& GraphComponent::dotPrint(std::ostream& os,
return os;
}
void GraphComponent::setDirty() { invalidate(); }
void GraphComponent::addNumericalConstraint(const ImplicitPtr_t& nm) {
invalidate();
numericalConstraints_.push_back(nm);
......
......@@ -210,10 +210,6 @@ bool Graph::getConfigErrorForEdgeLeaf(ConfigurationIn_t leafConfig,
return cs->isSatisfied(config, error);
}
ConstraintSetPtr_t Graph::configConstraint(const EdgePtr_t& edge) const {
return edge->targetConstraint();
}
ConstraintSetPtr_t Graph::targetConstraint(const EdgePtr_t& edge) const {
return edge->targetConstraint();
}
......
......@@ -62,7 +62,7 @@ void Roadmap::clear() {
void Roadmap::push_node(const core::NodePtr_t& n) {
Parent::push_node(n);
const RoadmapNodePtr_t& node = static_cast<const RoadmapNodePtr_t>(n);
const RoadmapNodePtr_t& node = static_cast<RoadmapNodePtr_t>(n);
statInsert(node);
leafCCs_.insert(node->leafConnectedComponent());
}
......@@ -80,7 +80,7 @@ void Roadmap::insertHistogram(const graph::HistogramPtr_t hist) {
histograms_.push_back(hist);
core::Nodes_t::const_iterator _node;
for (_node = nodes().begin(); _node != nodes().end(); ++_node)
hist->add(static_cast<const RoadmapNodePtr_t>(*_node));
hist->add(static_cast<RoadmapNodePtr_t>(*_node));
}
void Roadmap::constraintGraph(const graph::GraphPtr_t& graph) {
......@@ -154,8 +154,8 @@ void Roadmap::merge(const LeafConnectedCompPtr_t& cc1,
void Roadmap::impl_addEdge(const core::EdgePtr_t& edge) {
Parent::impl_addEdge(edge);
const RoadmapNodePtr_t& f = static_cast<const RoadmapNodePtr_t>(edge->from());
const RoadmapNodePtr_t& t = static_cast<const RoadmapNodePtr_t>(edge->to());
const RoadmapNodePtr_t& f = static_cast<RoadmapNodePtr_t>(edge->from());
const RoadmapNodePtr_t& t = static_cast<RoadmapNodePtr_t>(edge->to());
if (f->graphState() == t->graphState()) {
LeafConnectedCompPtr_t cc1(f->leafConnectedComponent());
LeafConnectedCompPtr_t cc2(t->leafConnectedComponent());
......
......@@ -73,7 +73,7 @@ inline void ConnectedComponent::serialize(Archive& ar,
if (!Archive::is_saving::value) {
RoadmapPtr_t roadmap = roadmap_.lock();
for (const core::NodePtr_t& node : nodes()) {
const RoadmapNodePtr_t& n = static_cast<const RoadmapNodePtr_t>(node);
const RoadmapNodePtr_t& n = static_cast<RoadmapNodePtr_t>(node);
graphStateMap_[roadmap->getState(n)].push_back(n);
}
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment