Namespaces | |
threading | |
vis | |
Classes | |
class | Footstep |
A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to the supporting leg) that can be performed by a humanoid robot. More... | |
class | FootstepPlanningVisNode |
class | PlanningState |
A class representing the robot's pose (i.e. position and orientation) in the underlying SBPL. More precisely a planning state is a discrete representation of the robot's supporting leg. More... | |
class | SimpleActionClient |
class | SimpleActionServer |
class | Singleton |
class | State |
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... | |
Enumerations | |
enum | Leg { RIGHT =0, LEFT =1, NOLEG =2 } |
Functions | |
double | angle_cell_2_state (int angle, double angle_bin_size) |
Calculate the respective (continuous) angle for a bin. More... | |
int | angle_state_2_cell (double angle, double angle_bin_size) |
Discretize a (continuous) angle into a bin. More... | |
unsigned int | calc_hash_tag (int x, int y, int theta, int leg, unsigned int hash_pred, unsigned int hash_succ, int max_hash_size) |
double | 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 | cont_val (int length, double cell_size) |
Calculates the continuous value for a length discretized in cell size. More... | |
msgs::ErrorStatus | determineGoalFeetPose (msgs::Feet &goal_feet, ros::ServiceClient &generate_feet_pose_client, const geometry_msgs::PoseStamped &goal_pose) |
msgs::ErrorStatus | determineStartFeetPose (msgs::Feet &start_feet, ros::ServiceClient &generate_feet_pose_client, const std_msgs::Header &header) |
int | disc_val (double length, double cell_size) |
Discretize a (continuous) value into cell size. More... | |
double | euclidean_distance (int x1, int y1, int x2, int y2) |
double | euclidean_distance (double x1, double y1, double x2, double y2) |
double | euclidean_distance (int x1, int y1, int z1, int x2, int y2, int z2) |
double | euclidean_distance (double x1, double y1, double z1, double x2, double y2, double z2) |
double | euclidean_distance_sq (int x1, int y1, int x2, int y2) |
double | euclidean_distance_sq (double x1, double y1, double x2, double y2) |
double | euclidean_distance_sq (int x1, int y1, int z1, int x2, int y2, int z2) |
double | euclidean_distance_sq (double x1, double y1, double z1, double x2, double y2, double z2) |
void | getDeltaStep (const msgs::Foot ¤t, const msgs::Foot &next, geometry_msgs::Pose &dstep) |
void | getDeltaStep (const tf::Pose ¤t, const tf::Pose &next, tf::Pose &dstep) |
bool | getFootSize (ros::NodeHandle &nh, geometry_msgs::Vector3 &foot_size) |
bool | getGridMapCoords (const nav_msgs::OccupancyGrid &map, double x, double y, int &map_x, int &map_y) |
bool | getGridMapIndex (const nav_msgs::OccupancyGrid &map, double x, double y, int &idx) |
bool | getRPY (ros::NodeHandle &nh, const std::string name, geometry_msgs::Vector3 &val) |
bool | getUpperBodyOriginShift (ros::NodeHandle &nh, geometry_msgs::Vector3 &upper_body_origin_shift) |
bool | getUpperBodySize (ros::NodeHandle &nh, geometry_msgs::Vector3 &upper_body_size) |
bool | getXYZ (ros::NodeHandle &nh, const std::string name, geometry_msgs::Vector3 &val) |
double | grid_cost (int x1, int y1, int x2, int y2, float cell_size) |
unsigned int | int_hash (int key) |
void | normalToQuaternion (const geometry_msgs::Vector3 &n, double yaw, geometry_msgs::Quaternion &q) |
void | normalToRP (const geometry_msgs::Vector3 &n, double yaw, double &r, double &p) |
double | parabol (double x, double y, double a_inv, double b_inv) |
double | pceil (double x, double prec) |
double | pfloor (double x, double prec) |
bool | 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 | pround (double x, double prec) |
void | quaternionToNormal (const geometry_msgs::Quaternion &q, geometry_msgs::Vector3 &n) |
void | quaternionToNormalYaw (const geometry_msgs::Quaternion &q, geometry_msgs::Vector3 &n, double &yaw) |
void | RPYToNormal (double r, double p, double y, geometry_msgs::Vector3 &n) |
int | 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... | |
std::string & | strip (std::string &s, const char c) |
std::string | strip_const (const std::string &s, const char c) |
msgs::ErrorStatus | transform (msgs::Foot &foot, ros::ServiceClient &transform_foot_pose_client, const std::string &target_frame) |
msgs::ErrorStatus | transform (msgs::Feet &feet, ros::ServiceClient &transform_feet_poses_client, const std::string &target_frame) |
msgs::ErrorStatus | transform (msgs::StepPlan &step_plan, ros::ServiceClient &transform_step_plan_client, const std::string &target_frame) |
template<typename T > | |
msgs::ErrorStatus | transformToPlannerFrame (T &p, ros::ServiceClient &foot_pose_transformer_client) |
template<typename T > | |
msgs::ErrorStatus | transformToRobotFrame (T &p, ros::ServiceClient &foot_pose_transformer_client) |
Variables | |
static const int | cvMmScale = 1000 |
Used to scale continuous values in meter to discrete values in mm. More... | |
static const double | FLOAT_CMP_THR = 0.0001 |
static const double | TWO_PI = 2 * M_PI |
|
inline |
|
inline |
|
inline |
|
inline |
Calculate the respective (continuous) state value for a cell. (Should be used to get a State from a discretized PlanningState.)
|
inline |
msgs::ErrorStatus vigir_footstep_planning::determineGoalFeetPose | ( | msgs::Feet & | goal_feet, |
ros::ServiceClient & | generate_feet_pose_client, | ||
const geometry_msgs::PoseStamped & | goal_pose | ||
) |
Definition at line 43 of file helper.cpp.
msgs::ErrorStatus vigir_footstep_planning::determineStartFeetPose | ( | msgs::Feet & | start_feet, |
ros::ServiceClient & | generate_feet_pose_client, | ||
const std_msgs::Header & | header | ||
) |
Definition at line 5 of file helper.cpp.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
void vigir_footstep_planning::getDeltaStep | ( | const msgs::Foot & | current, |
const msgs::Foot & | next, | ||
geometry_msgs::Pose & | dstep | ||
) |
bool vigir_footstep_planning::getFootSize | ( | ros::NodeHandle & | nh, |
geometry_msgs::Vector3 & | foot_size | ||
) |
Definition at line 130 of file helper.cpp.
bool vigir_footstep_planning::getGridMapCoords | ( | const nav_msgs::OccupancyGrid & | map, |
double | x, | ||
double | y, | ||
int & | map_x, | ||
int & | map_y | ||
) |
Definition at line 147 of file helper.cpp.
bool vigir_footstep_planning::getGridMapIndex | ( | const nav_msgs::OccupancyGrid & | map, |
double | x, | ||
double | y, | ||
int & | idx | ||
) |
Definition at line 159 of file helper.cpp.
bool vigir_footstep_planning::getRPY | ( | ros::NodeHandle & | nh, |
const std::string | name, | ||
geometry_msgs::Vector3 & | val | ||
) |
Definition at line 116 of file helper.cpp.
bool vigir_footstep_planning::getUpperBodyOriginShift | ( | ros::NodeHandle & | nh, |
geometry_msgs::Vector3 & | upper_body_origin_shift | ||
) |
Definition at line 140 of file helper.cpp.
bool vigir_footstep_planning::getUpperBodySize | ( | ros::NodeHandle & | nh, |
geometry_msgs::Vector3 & | upper_body_size | ||
) |
Definition at line 135 of file helper.cpp.
bool vigir_footstep_planning::getXYZ | ( | ros::NodeHandle & | nh, |
const std::string | name, | ||
geometry_msgs::Vector3 & | val | ||
) |
Definition at line 102 of file helper.cpp.
|
inline |
|
inline |
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 | ||
) |
|
inline |
|
inline |
|
inline |
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.
edges | (x,y)-points defining the polygon. |
Check http://geomalgorithms.com/a03-_inclusion.html for further details.
|
inline |
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 | ||
) |
|
inline |
Discretize a (continuous) state value into a cell. (Should be used to discretize a State to a PlanningState.)
|
inline |
|
inline |
msgs::ErrorStatus vigir_footstep_planning::transform | ( | msgs::Foot & | foot, |
ros::ServiceClient & | transform_foot_pose_client, | ||
const std::string & | target_frame | ||
) |
Definition at line 58 of file helper.cpp.
msgs::ErrorStatus vigir_footstep_planning::transform | ( | msgs::Feet & | feet, |
ros::ServiceClient & | transform_feet_poses_client, | ||
const std::string & | target_frame | ||
) |
Definition at line 72 of file helper.cpp.
msgs::ErrorStatus vigir_footstep_planning::transform | ( | msgs::StepPlan & | step_plan, |
ros::ServiceClient & | transform_step_plan_client, | ||
const std::string & | target_frame | ||
) |
Definition at line 86 of file helper.cpp.
msgs::ErrorStatus vigir_footstep_planning::transformToPlannerFrame | ( | T & | p, |
ros::ServiceClient & | foot_pose_transformer_client | ||
) |
msgs::ErrorStatus vigir_footstep_planning::transformToRobotFrame | ( | T & | p, |
ros::ServiceClient & | foot_pose_transformer_client | ||
) |
|
static |
|
static |