Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include <footstep_planner/State.h>
00022
00023
00024 namespace footstep_planner
00025 {
00026 State::State()
00027 : ivX(0.0), ivY(0.0), ivTheta(0.0), ivLeg(NOLEG)
00028 {}
00029
00030
00031 State::State(double x, double y, double theta, Leg leg)
00032 : ivX(x), ivY(y), ivTheta(theta), ivLeg(leg)
00033 {}
00034
00035
00036 State::~State()
00037 {}
00038
00039
00040 bool
00041 State::operator ==(const State& s2)
00042 const
00043 {
00044 return (fabs(ivX - s2.getX()) < FLOAT_CMP_THR &&
00045 fabs(ivY - s2.getY()) < FLOAT_CMP_THR &&
00046 fabs(angles::shortest_angular_distance(ivTheta, s2.getTheta()))
00047 < FLOAT_CMP_THR &&
00048 ivLeg == s2.getLeg());
00049 }
00050
00051
00052 bool
00053 State::operator !=(const State& s2)
00054 const
00055 {
00056 return not (*this == s2);
00057 }
00058 }