|
double | vigir_footstep_planning::angle_cell_2_state (int angle, double angle_bin_size) |
| Calculate the respective (continuous) angle for a bin. More...
|
|
int | vigir_footstep_planning::angle_state_2_cell (double angle, double angle_bin_size) |
| Discretize a (continuous) angle into a bin. More...
|
|
unsigned int | vigir_footstep_planning::calc_hash_tag (int x, int y, int theta, int leg, unsigned int hash_pred, unsigned int hash_succ, int max_hash_size) |
|
double | vigir_footstep_planning::cell_2_state (int value, double cell_size) |
| Calculate the respective (continuous) state value for a cell. (Should be used to get a State from a discretized PlanningState.) More...
|
|
double | vigir_footstep_planning::cont_val (int length, double cell_size) |
| Calculates the continuous value for a length discretized in cell size. More...
|
|
int | vigir_footstep_planning::disc_val (double length, double cell_size) |
| Discretize a (continuous) value into cell size. More...
|
|
double | vigir_footstep_planning::euclidean_distance (int x1, int y1, int x2, int y2) |
|
double | vigir_footstep_planning::euclidean_distance (double x1, double y1, double x2, double y2) |
|
double | vigir_footstep_planning::euclidean_distance (int x1, int y1, int z1, int x2, int y2, int z2) |
|
double | vigir_footstep_planning::euclidean_distance (double x1, double y1, double z1, double x2, double y2, double z2) |
|
double | vigir_footstep_planning::euclidean_distance_sq (int x1, int y1, int x2, int y2) |
|
double | vigir_footstep_planning::euclidean_distance_sq (double x1, double y1, double x2, double y2) |
|
double | vigir_footstep_planning::euclidean_distance_sq (int x1, int y1, int z1, int x2, int y2, int z2) |
|
double | vigir_footstep_planning::euclidean_distance_sq (double x1, double y1, double z1, double x2, double y2, double z2) |
|
void | vigir_footstep_planning::getDeltaStep (const msgs::Foot ¤t, const msgs::Foot &next, geometry_msgs::Pose &dstep) |
|
void | vigir_footstep_planning::getDeltaStep (const tf::Pose ¤t, const tf::Pose &next, tf::Pose &dstep) |
|
double | vigir_footstep_planning::grid_cost (int x1, int y1, int x2, int y2, float cell_size) |
|
unsigned int | vigir_footstep_planning::int_hash (int key) |
|
void | vigir_footstep_planning::normalToQuaternion (const geometry_msgs::Vector3 &n, double yaw, geometry_msgs::Quaternion &q) |
|
void | vigir_footstep_planning::normalToRP (const geometry_msgs::Vector3 &n, double yaw, double &r, double &p) |
|
double | vigir_footstep_planning::parabol (double x, double y, double a_inv, double b_inv) |
|
double | vigir_footstep_planning::pceil (double x, double prec) |
|
double | vigir_footstep_planning::pfloor (double x, double prec) |
|
bool | vigir_footstep_planning::pointWithinPolygon (int x, int y, const std::vector< std::pair< int, int > > &edges) |
| Crossing number method to determine whether a point lies within a polygon or not. More...
|
|
double | vigir_footstep_planning::pround (double x, double prec) |
|
void | vigir_footstep_planning::quaternionToNormal (const geometry_msgs::Quaternion &q, geometry_msgs::Vector3 &n) |
|
void | vigir_footstep_planning::quaternionToNormalYaw (const geometry_msgs::Quaternion &q, geometry_msgs::Vector3 &n, double &yaw) |
|
void | vigir_footstep_planning::RPYToNormal (double r, double p, double y, geometry_msgs::Vector3 &n) |
|
int | vigir_footstep_planning::state_2_cell (float value, float cell_size) |
| Discretize a (continuous) state value into a cell. (Should be used to discretize a State to a PlanningState.) More...
|
|