footprint.h 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106
  1. #ifndef COSTMAP_2D_FOOTPRINT_H
  2. #define COSTMAP_2D_FOOTPRINT_H
  3. #include <ros/ros.h>
  4. #include <geometry_msgs/Polygon.h>
  5. #include <geometry_msgs/PolygonStamped.h>
  6. #include <geometry_msgs/Point.h>
  7. #include <geometry_msgs/Point32.h>
  8. namespace costmap_2d
  9. {
  10. /**
  11. * @brief Calculate the extreme distances for the footprint
  12. *
  13. * @param footprint The footprint to examine
  14. * @param min_dist Output parameter of the minimum distance
  15. * @param max_dist Output parameter of the maximum distance
  16. */
  17. void calculateMinAndMaxDistances(const std::vector<geometry_msgs::Point>& footprint,
  18. double& min_dist, double& max_dist);
  19. /**
  20. * @brief Convert Point32 to Point
  21. */
  22. geometry_msgs::Point toPoint(geometry_msgs::Point32 pt);
  23. /**
  24. * @brief Convert Point to Point32
  25. */
  26. geometry_msgs::Point32 toPoint32(geometry_msgs::Point pt);
  27. /**
  28. * @brief Convert vector of Points to Polygon msg
  29. */
  30. geometry_msgs::Polygon toPolygon(std::vector<geometry_msgs::Point> pts);
  31. /**
  32. * @brief Convert Polygon msg to vector of Points.
  33. */
  34. std::vector<geometry_msgs::Point> toPointVector(geometry_msgs::Polygon polygon);
  35. /**
  36. * @brief Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
  37. * @param x The x position of the robot
  38. * @param y The y position of the robot
  39. * @param theta The orientation of the robot
  40. * @param footprint_spec Basic shape of the footprint
  41. * @param oriented_footprint Will be filled with the points in the oriented footprint of the robot
  42. */
  43. void transformFootprint(double x, double y, double theta, const std::vector<geometry_msgs::Point>& footprint_spec,
  44. std::vector<geometry_msgs::Point>& oriented_footprint);
  45. /**
  46. * @brief Given a pose and base footprint, build the oriented footprint of the robot (PolygonStamped)
  47. * @param x The x position of the robot
  48. * @param y The y position of the robot
  49. * @param theta The orientation of the robot
  50. * @param footprint_spec Basic shape of the footprint
  51. * @param oriented_footprint Will be filled with the points in the oriented footprint of the robot
  52. */
  53. void transformFootprint(double x, double y, double theta, const std::vector<geometry_msgs::Point>& footprint_spec,
  54. geometry_msgs::PolygonStamped & oriented_footprint);
  55. /**
  56. * @brief Create a circular footprint from a given radius
  57. */
  58. std::vector<geometry_msgs::Point> makeFootprintFromRadius(double radius);
  59. /**
  60. * @brief Make the footprint from the given string.
  61. *
  62. * Format should be bracketed array of arrays of floats, like so: [[1.0, 2.2], [3.3, 4.2], ...]
  63. *
  64. */
  65. bool makeFootprintFromString(const std::string& footprint_string, std::vector<geometry_msgs::Point>& footprint);
  66. /**
  67. * @brief Read the ros-params "footprint" and/or "robot_radius" from
  68. * the given NodeHandle using searchParam() to go up the tree.
  69. */
  70. std::vector<geometry_msgs::Point> makeFootprintFromParams(ros::NodeHandle& nh);
  71. /**
  72. * @brief Create the footprint from the given XmlRpcValue.
  73. *
  74. * @param footprint_xmlrpc should be an array of arrays, where the
  75. * top-level array should have 3 or more elements, and the
  76. * sub-arrays should all have exactly 2 elements (x and y
  77. * coordinates).
  78. *
  79. * @param full_param_name this is the full name of the rosparam from
  80. * which the footprint_xmlrpc value came. It is used only for
  81. * reporting errors. */
  82. std::vector<geometry_msgs::Point> makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc,
  83. const std::string& full_param_name);
  84. /** @brief Write the current unpadded_footprint_ to the "footprint"
  85. * parameter of the given NodeHandle so that dynamic_reconfigure
  86. * will see the new value. */
  87. void writeFootprintToParam(ros::NodeHandle& nh, const std::vector<geometry_msgs::Point>& footprint);
  88. } // end namespace costmap_2d
  89. #endif // COSTMAP_2D_FOOTPRINT_H