Public Member Functions | Private Member Functions | Private Attributes
vigir_footstep_planning::State Class Reference

A class representing the robot's pose (i.e. position and orientation) in the (continuous) world view. More precisely a state points to the robot's supporting leg. More...

#include <state.h>

List of all members.

Public Member Functions

const geometry_msgs::Vector3getBodyVelocity () const
double getCost () const
void getFoot (msgs::Foot &foot) const
double getGroundContactSupport () const
Leg getLeg () const
const geometry_msgs::Vector3getNormal () const
double getNormalX () const
double getNormalY () const
double getNormalZ () const
double getPitch () const
const tf::PosegetPose () const
tf::PosegetPose ()
double getRisk () const
double getRoll () const
void getStep (msgs::Step &step) const
double getStepDuration () const
double getSwayDistance () const
double getSwayDuration () const
double getSwingDistance () const
double getSwingHeight () const
double getX () const
double getY () const
double getYaw () const
double getZ () const
bool operator!= (const State &s2) const
 Inequality operator for two states (negates the equality operator).
bool operator== (const State &s2) const
 Compare two states on equality of x, y, theta, leg upon a certain degree of float precision.
void setBodyVelocity (const geometry_msgs::Vector3 &body_vel)
void setCost (double cost)
void setGroundContactSupport (double ground_contact_support)
void setLeg (Leg leg)
void setNormal (const geometry_msgs::Vector3 &normal)
void setNormal (double x, double y, double z)
void setOrientation (const geometry_msgs::Quaternion &q)
void setPitch (double pitch)
void setPosition (const geometry_msgs::Point &position)
void setRisk (double risk)
void setRoll (double roll)
void setRPY (double roll, double pitch, double yaw)
void setStepDuration (double step_duration)
void setSwayDistance (double sway_distance)
void setSwayDuration (double sway_duration)
void setSwingDistance (double swing_distance)
void setSwingHeight (double swing_height)
void setX (double x)
void setY (double y)
void setYaw (double yaw)
void setZ (double z)
 State ()
 State (double x, double y, double z, double roll, double pitch, double yaw, Leg leg)
 State (const geometry_msgs::Vector3 &position, double roll, double pitch, double yaw, Leg leg)
 State (const geometry_msgs::Vector3 &position, const geometry_msgs::Vector3 &normal, double yaw, Leg leg)
 State (const geometry_msgs::Pose &pose, Leg leg)
 State (const tf::Transform &t, Leg leg)
 State (const msgs::Foot foot)
 State (const msgs::Step step)
 ~State ()

Private Member Functions

void recomputeNormal ()

Private Attributes

geometry_msgs::Vector3 body_vel
double cost
double ivGroundContactSupport
 percentage of ground contact support (0.0 - 1.0 = 100%)
Leg ivLeg
 The robot's supporting leg.
geometry_msgs::Vector3 ivNormal
 The normal of foot in world.
double ivPitch
tf::Pose ivPose
double ivRoll
 The robot's orientation.
double ivStepDuration
double ivSwayDuration
double ivSwingHeight
double ivYaw
double risk
double sway_distance
double swing_distance

Detailed Description

A class representing the robot's pose (i.e. position and orientation) in the (continuous) world view. More precisely a state points to the robot's supporting leg.

Definition at line 49 of file state.h.


Constructor & Destructor Documentation

Definition at line 5 of file state.cpp.

vigir_footstep_planning::State::State ( double  x,
double  y,
double  z,
double  roll,
double  pitch,
double  yaw,
Leg  leg 
)

Definition at line 27 of file state.cpp.

vigir_footstep_planning::State::State ( const geometry_msgs::Vector3 position,
double  roll,
double  pitch,
double  yaw,
Leg  leg 
)

Definition at line 48 of file state.cpp.

vigir_footstep_planning::State::State ( const geometry_msgs::Vector3 position,
const geometry_msgs::Vector3 normal,
double  yaw,
Leg  leg 
)

Definition at line 53 of file state.cpp.

Definition at line 71 of file state.cpp.

vigir_footstep_planning::State::State ( const msgs::Foot  foot)

Definition at line 107 of file state.cpp.

vigir_footstep_planning::State::State ( const msgs::Step  step)

Definition at line 112 of file state.cpp.

Definition at line 120 of file state.cpp.


Member Function Documentation

Definition at line 114 of file state.h.

double vigir_footstep_planning::State::getCost ( ) const [inline]

Definition at line 115 of file state.h.

void vigir_footstep_planning::State::getFoot ( msgs::Foot &  foot) const

Definition at line 206 of file state.cpp.

Definition at line 113 of file state.h.

Definition at line 112 of file state.h.

Definition at line 103 of file state.h.

double vigir_footstep_planning::State::getNormalX ( ) const [inline]

Definition at line 104 of file state.h.

double vigir_footstep_planning::State::getNormalY ( ) const [inline]

Definition at line 105 of file state.h.

double vigir_footstep_planning::State::getNormalZ ( ) const [inline]

Definition at line 106 of file state.h.

double vigir_footstep_planning::State::getPitch ( ) const [inline]

Definition at line 101 of file state.h.

Definition at line 118 of file state.h.

Definition at line 119 of file state.h.

double vigir_footstep_planning::State::getRisk ( ) const [inline]

Definition at line 116 of file state.h.

double vigir_footstep_planning::State::getRoll ( ) const [inline]

Definition at line 100 of file state.h.

void vigir_footstep_planning::State::getStep ( msgs::Step &  step) const

Definition at line 195 of file state.cpp.

Definition at line 109 of file state.h.

Definition at line 110 of file state.h.

Definition at line 108 of file state.h.

Definition at line 111 of file state.h.

Definition at line 107 of file state.h.

double vigir_footstep_planning::State::getX ( ) const [inline]

Definition at line 97 of file state.h.

double vigir_footstep_planning::State::getY ( ) const [inline]

Definition at line 98 of file state.h.

double vigir_footstep_planning::State::getYaw ( ) const [inline]

Definition at line 102 of file state.h.

double vigir_footstep_planning::State::getZ ( ) const [inline]

Definition at line 99 of file state.h.

bool vigir_footstep_planning::State::operator!= ( const State s2) const

Inequality operator for two states (negates the equality operator).

Definition at line 134 of file state.cpp.

bool vigir_footstep_planning::State::operator== ( const State s2) const

Compare two states on equality of x, y, theta, leg upon a certain degree of float precision.

Definition at line 123 of file state.cpp.

Definition at line 215 of file state.cpp.

Definition at line 93 of file state.h.

void vigir_footstep_planning::State::setCost ( double  cost) [inline]

Definition at line 94 of file state.h.

void vigir_footstep_planning::State::setGroundContactSupport ( double  ground_contact_support) [inline]

Definition at line 92 of file state.h.

Definition at line 91 of file state.h.

Definition at line 165 of file state.cpp.

void vigir_footstep_planning::State::setNormal ( double  x,
double  y,
double  z 
)

Definition at line 186 of file state.cpp.

void vigir_footstep_planning::State::setOrientation ( const geometry_msgs::Quaternion &  q)

Definition at line 146 of file state.cpp.

void vigir_footstep_planning::State::setPitch ( double  pitch) [inline]

Definition at line 80 of file state.h.

Definition at line 139 of file state.cpp.

void vigir_footstep_planning::State::setRisk ( double  risk) [inline]

Definition at line 95 of file state.h.

void vigir_footstep_planning::State::setRoll ( double  roll) [inline]

Definition at line 79 of file state.h.

void vigir_footstep_planning::State::setRPY ( double  roll,
double  pitch,
double  yaw 
)

Definition at line 155 of file state.cpp.

void vigir_footstep_planning::State::setStepDuration ( double  step_duration) [inline]

Definition at line 88 of file state.h.

void vigir_footstep_planning::State::setSwayDistance ( double  sway_distance) [inline]

Definition at line 89 of file state.h.

void vigir_footstep_planning::State::setSwayDuration ( double  sway_duration) [inline]

Definition at line 87 of file state.h.

void vigir_footstep_planning::State::setSwingDistance ( double  swing_distance) [inline]

Definition at line 90 of file state.h.

void vigir_footstep_planning::State::setSwingHeight ( double  swing_height) [inline]

Definition at line 86 of file state.h.

void vigir_footstep_planning::State::setX ( double  x) [inline]

Definition at line 75 of file state.h.

void vigir_footstep_planning::State::setY ( double  y) [inline]

Definition at line 76 of file state.h.

void vigir_footstep_planning::State::setYaw ( double  yaw) [inline]

Definition at line 81 of file state.h.

void vigir_footstep_planning::State::setZ ( double  z) [inline]

Definition at line 77 of file state.h.


Member Data Documentation

Definition at line 144 of file state.h.

Definition at line 149 of file state.h.

percentage of ground contact support (0.0 - 1.0 = 100%)

Definition at line 142 of file state.h.

The robot's supporting leg.

Definition at line 129 of file state.h.

The normal of foot in world.

Definition at line 136 of file state.h.

Definition at line 133 of file state.h.

Definition at line 126 of file state.h.

The robot's orientation.

Definition at line 132 of file state.h.

Definition at line 139 of file state.h.

Definition at line 138 of file state.h.

Definition at line 137 of file state.h.

Definition at line 134 of file state.h.

Definition at line 150 of file state.h.

Definition at line 146 of file state.h.

Definition at line 147 of file state.h.


The documentation for this class was generated from the following files:


vigir_footstep_planning_lib
Author(s): Alexander Stumpf
autogenerated on Sat Jun 8 2019 19:01:44