29 #ifndef VIGIR_FOOTSTEP_PLANNING_VIS_H__ 30 #define VIGIR_FOOTSTEP_PLANNING_VIS_H__ 33 #include <sensor_msgs/PointCloud2.h> 36 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h> 37 #include <vigir_footstep_planning_msgs/visualization.h> 47 bool operator() (
const msgs::Step& lhs,
const msgs::Step& rhs)
const 55 for (
size_t i = 0; i < 3; i++)
57 if (lhs_a[i] < rhs_a[i])
59 else if (lhs_a[i] > rhs_a[i])
65 void toArray(
const msgs::Step s,
double (&a)[3])
const 67 a[0] = s.foot.pose.position.x;
68 a[1] = s.foot.pose.position.y;
69 a[2] = s.foot.pose.position.z;
73 void publishFeet(
ros::Publisher& pub,
const msgs::Feet& feet,
const geometry_msgs::Vector3& foot_size,
const std_msgs::ColorRGBA& color);
77 void publishStepPlan(
ros::Publisher& pub,
const msgs::StepPlan& step_plan,
const geometry_msgs::Vector3& foot_size, visualization_msgs::MarkerArray& last_step_plan_vis,
bool add_step_index =
true);
78 void publishUpperBody(
ros::Publisher& pub,
const msgs::StepPlan& step_plan,
const geometry_msgs::Vector3& upper_body_size,
const geometry_msgs::Vector3& upper_body_origin_shift, visualization_msgs::MarkerArray& last_upper_body_vis,
bool add_step_index =
true);