footstep_planning_vis.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2017, Alexander Stumpf, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef VIGIR_FOOTSTEP_PLANNING_VIS_H__
30 #define VIGIR_FOOTSTEP_PLANNING_VIS_H__
31 
32 #include <ros/ros.h>
33 #include <sensor_msgs/PointCloud2.h>
35 
36 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
37 #include <vigir_footstep_planning_msgs/visualization.h>
38 
39 
40 
42 {
43 namespace vis
44 {
46 {
47  bool operator() (const msgs::Step& lhs, const msgs::Step& rhs) const
48  {
49  double lhs_a[3];
50  toArray(lhs, lhs_a);
51  double rhs_a[3];
52  toArray(rhs, rhs_a);
53 
54  // we can't visualize orientation, thus we ignore it
55  for (size_t i = 0; i < 3; i++)
56  {
57  if (lhs_a[i] < rhs_a[i])
58  return true;
59  else if (lhs_a[i] > rhs_a[i])
60  return false;
61  }
62  return false;
63  }
64 
65  void toArray(const msgs::Step s, double (&a)[3]) const
66  {
67  a[0] = s.foot.pose.position.x;
68  a[1] = s.foot.pose.position.y;
69  a[2] = s.foot.pose.position.z;
70  }
71 };
72 
73 void publishFeet(ros::Publisher& pub, const msgs::Feet& feet, const geometry_msgs::Vector3& foot_size, const std_msgs::ColorRGBA& color);
74 void publishStart(ros::Publisher& pub, const msgs::Feet& feet, const geometry_msgs::Vector3& foot_size);
75 void publishGoal(ros::Publisher& pub, const msgs::Feet& feet, const geometry_msgs::Vector3& foot_size);
76 
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);
79 void publishPath(ros::Publisher& pub, const msgs::StepPlan& step_plan);
80 
81 void clearFeet(ros::Publisher& pub, const std_msgs::Header& header);
82 void clearMarkerArray(ros::Publisher& pub, visualization_msgs::MarkerArray& last_step_plan_vis);
83 void clearPath(ros::Publisher& pub, const std_msgs::Header& header);
84 
85 void publishRecentlyVistedSteps(ros::Publisher& pub, const std::vector<msgs::Step>& recently_visited_steps, const std_msgs::Header& header);
86 void publishVistedSteps(ros::Publisher& pub, const std::vector<msgs::Step>& visited_steps, const std_msgs::Header& header);
87 void publishVistedSteps(ros::Publisher& pub, const std::set<msgs::Step, StepMsgVisCompare>& visited_steps, const std_msgs::Header& header);
88 }
89 }
90 
91 #endif
bool operator()(const msgs::Step &lhs, const msgs::Step &rhs) const
void publishVistedSteps(ros::Publisher &pub, const std::vector< msgs::Step > &visited_steps, const std_msgs::Header &header)
void publishFeet(ros::Publisher &pub, const msgs::Feet &feet, const geometry_msgs::Vector3 &foot_size, const std_msgs::ColorRGBA &color)
void toArray(const msgs::Step s, double(&a)[3]) const
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)
void publishRecentlyVistedSteps(ros::Publisher &pub, const std::vector< msgs::Step > &recently_visited_steps, const std_msgs::Header &header)
void publishGoal(ros::Publisher &pub, const msgs::Feet &feet, const geometry_msgs::Vector3 &foot_size)
void publishStart(ros::Publisher &pub, const msgs::Feet &feet, const geometry_msgs::Vector3 &foot_size)
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)
void clearPath(ros::Publisher &pub, const std_msgs::Header &header)
void clearMarkerArray(ros::Publisher &pub, visualization_msgs::MarkerArray &last_step_plan_vis)
void publishPath(ros::Publisher &pub, const msgs::StepPlan &step_plan)
void clearFeet(ros::Publisher &pub, const std_msgs::Header &header)


vigir_footstep_planning_lib
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:47:33