Main Page
Namespaces
Classes
Files
File List
File Members
src
State.cpp
Go to the documentation of this file.
1
/*
2
* A footstep planner for humanoid robots
3
*
4
* Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
5
* http://www.ros.org/wiki/footstep_planner
6
*
7
*
8
* This program is free software: you can redistribute it and/or modify
9
* it under the terms of the GNU General Public License as published by
10
* the Free Software Foundation, version 3.
11
*
12
* This program is distributed in the hope that it will be useful,
13
* but WITHOUT ANY WARRANTY; without even the implied warranty of
14
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15
* GNU General Public License for more details.
16
*
17
* You should have received a copy of the GNU General Public License
18
* along with this program. If not, see <http://www.gnu.org/licenses/>.
19
*/
20
21
#include <
footstep_planner/State.h
>
22
23
24
namespace
footstep_planner
25
{
26
State::State
()
27
: ivX(0.0), ivY(0.0), ivTheta(0.0), ivLeg(
NOLEG
)
28
{}
29
30
31
State::State
(
double
x,
double
y,
double
theta
,
Leg
leg)
32
:
ivX
(x),
ivY
(y),
ivTheta
(theta),
ivLeg
(leg)
33
{}
34
35
36
State::~State
()
37
{}
38
39
40
bool
41
State::operator ==
(
const
State
& s2)
42
const
43
{
44
return
(fabs(
ivX
- s2.
getX
()) <
FLOAT_CMP_THR
&&
45
fabs(
ivY
- s2.
getY
()) <
FLOAT_CMP_THR
&&
46
fabs(
angles::shortest_angular_distance
(
ivTheta
, s2.
getTheta
()))
47
<
FLOAT_CMP_THR
&&
48
ivLeg
== s2.
getLeg
());
49
}
50
51
52
bool
53
State::operator !=
(
const
State
& s2)
54
const
55
{
56
return
not (*
this
== s2);
57
}
58
}
// end of namespace
footstep_planner::Leg
Leg
Definition:
helper.h:41
footstep_planner::State::getTheta
double getTheta() const
Definition:
State.h:48
footstep_planner::State::operator!=
bool operator!=(const State &s2) const
Inequality operator for two states (negates the equality operator).
Definition:
State.cpp:53
footstep_planner::State::operator==
bool operator==(const State &s2) const
Compare two states on equality of x, y, theta, leg upon a certain degree of float precision...
Definition:
State.cpp:41
footstep_planner::FLOAT_CMP_THR
static const double FLOAT_CMP_THR
Definition:
helper.h:39
footstep_planner::State::State
State()
Definition:
State.cpp:26
footstep_planner::State::getX
double getX() const
Definition:
State.h:46
footstep_planner::NOLEG
Definition:
helper.h:41
footstep_planner::State
A class representing the robot's pose (i.e. position and orientation) in the (continuous) world view...
Definition:
State.h:34
footstep_planner::State::ivX
double ivX
The robot's position in x direction.
Definition:
State.h:65
footstep_planner::State::getY
double getY() const
Definition:
State.h:47
footstep_planner::State::ivTheta
double ivTheta
The robot's orientation.
Definition:
State.h:69
plan_footsteps.theta
theta
Definition:
plan_footsteps.py:38
footstep_planner::State::ivLeg
Leg ivLeg
The robot's supporting leg.
Definition:
State.h:71
footstep_planner::State::~State
~State()
Definition:
State.cpp:36
State.h
footstep_planner::State::ivY
double ivY
The robot's position in y direction.
Definition:
State.h:67
footstep_planner::State::getLeg
Leg getLeg() const
Definition:
State.h:49
angles::shortest_angular_distance
def shortest_angular_distance(from_angle, to_angle)
footstep_planner
Definition:
Footstep.h:28
footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24