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>
Public Member Functions | |
| const geometry_msgs::Vector3 & | getBodyVelocity () const |
| double | getCost () const |
| void | getFoot (msgs::Foot &foot) const |
| double | getGroundContactSupport () const |
| Leg | getLeg () const |
| const geometry_msgs::Vector3 & | getNormal () const |
| double | getNormalX () const |
| double | getNormalY () const |
| double | getNormalZ () const |
| double | getPitch () const |
| const tf::Pose & | getPose () const |
| tf::Pose & | getPose () |
| 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). More... | |
| bool | operator== (const State &s2) const |
| Compare two states on equality of x, y, theta, leg upon a certain degree of float precision. More... | |
| 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%) More... | |
| Leg | ivLeg |
| The robot's supporting leg. More... | |
| geometry_msgs::Vector3 | ivNormal |
| The normal of foot in world. More... | |
| double | ivPitch |
| tf::Pose | ivPose |
| double | ivRoll |
| The robot's orientation. More... | |
| double | ivStepDuration |
| double | ivSwayDuration |
| double | ivSwingHeight |
| double | ivYaw |
| double | risk |
| double | sway_distance |
| double | swing_distance |
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.
| vigir_footstep_planning::State::State | ( | double | x, |
| double | y, | ||
| double | z, | ||
| double | roll, | ||
| double | pitch, | ||
| double | yaw, | ||
| Leg | leg | ||
| ) |
| vigir_footstep_planning::State::State | ( | const geometry_msgs::Vector3 & | position, |
| double | roll, | ||
| double | pitch, | ||
| double | yaw, | ||
| Leg | leg | ||
| ) |
| vigir_footstep_planning::State::State | ( | const geometry_msgs::Vector3 & | position, |
| const geometry_msgs::Vector3 & | normal, | ||
| double | yaw, | ||
| Leg | leg | ||
| ) |
| vigir_footstep_planning::State::State | ( | const geometry_msgs::Pose & | pose, |
| Leg | leg | ||
| ) |
| vigir_footstep_planning::State::State | ( | const tf::Transform & | t, |
| Leg | leg | ||
| ) |
| vigir_footstep_planning::State::State | ( | const msgs::Foot | foot | ) |
| vigir_footstep_planning::State::State | ( | const msgs::Step | step | ) |
|
inline |
|
inline |
| void vigir_footstep_planning::State::getFoot | ( | msgs::Foot & | foot | ) | const |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
| void vigir_footstep_planning::State::getStep | ( | msgs::Step & | step | ) | const |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
| bool vigir_footstep_planning::State::operator!= | ( | const State & | s2 | ) | const |
| bool vigir_footstep_planning::State::operator== | ( | const State & | s2 | ) | const |
|
private |
|
inline |
|
inline |
|
inline |
|
inline |
| void vigir_footstep_planning::State::setNormal | ( | const geometry_msgs::Vector3 & | normal | ) |
| void vigir_footstep_planning::State::setNormal | ( | double | x, |
| double | y, | ||
| double | z | ||
| ) |
| void vigir_footstep_planning::State::setOrientation | ( | const geometry_msgs::Quaternion & | q | ) |
|
inline |
| void vigir_footstep_planning::State::setPosition | ( | const geometry_msgs::Point & | position | ) |
|
inline |
|
inline |
| void vigir_footstep_planning::State::setRPY | ( | double | roll, |
| double | pitch, | ||
| double | yaw | ||
| ) |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |