35 #include <boost/lexical_cast.hpp> 37 #include <geometry_msgs/PoseStamped.h> 39 #include <visualization_msgs/MarkerArray.h> 62 createCylinders(
const std::vector<CylindricalShell> &list,
const std::string &frame);
69 createHandleNumbers(
const std::vector<std::vector<CylindricalShell> > &handles,
const std::string &frame);
81 createHandles(
const std::vector<std::vector<CylindricalShell> > &handles,
const std::string &frame,
82 std::vector<MarkerArray> &marker_arrays,
MarkerArray &all_handle_markers);
Visualizer(double marker_lifetime)
Constructor. Set the lifetime of markers in RViz.
MarkerArray createCylinders(const std::vector< CylindricalShell > &list, const std::string &frame)
Create a MarkerArray message from a list of cylindrical shells.
visualization_msgs::MarkerArray MarkerArray
MarkerArray createHandleNumbers(const std::vector< std::vector< CylindricalShell > > &handles, const std::string &frame)
Create a MarkerArray message from a list of cylindrical shells.
void createHandles(const std::vector< std::vector< CylindricalShell > > &handles, const std::string &frame, std::vector< MarkerArray > &marker_arrays, MarkerArray &all_handle_markers)
Create a list of MarkerArray messages and a MarkerArray from a list of handles. The former represents...
Visualizer creates ROS messages to visualize the results of the localization in RViz. The possible objects that can be visualized are: neighborhoods, cylindrical shells, and handles.