Publishes and keeps track of debug grasp markers. More...
#include <grasp_marker_publisher.h>
Public Member Functions | |
unsigned int | addGraspMarker (const geometry_msgs::PoseStamped &marker_pose) |
Adds and publishes a marker with default color (blue). Returns the id of the new marker. | |
void | clearAllMarkers () |
Removes and deletes all currently displayed markers. | |
void | colorGraspMarker (unsigned int marker_id, float r, float g, float b) |
Sets the color of the grasp marker with the given id. | |
GraspMarkerPublisher () | |
Advertises the marker publishing topic with default options. | |
GraspMarkerPublisher (std::string marker_out_name, std::string ns_append, double publishing_rate) | |
Advertises the marker topic with aadvanced options. | |
void | setMarkerPose (unsigned int marker_id, const geometry_msgs::PoseStamped &marker_pose) |
Sets the pose of the marker with the given id. | |
void | setNamespaceSuffix (std::string ns_append) |
Sets the string to append to the namespace that the markers are published on. | |
~GraspMarkerPublisher () | |
Joins the publishing thread, if any. | |
Private Member Functions | |
void | init (std::string marker_out_name, std::string ns_append, double publishing_rate) |
Operations common to all constructors, sets all the possible options. | |
void | publishingThread () |
Re-publishes all marker periodically. | |
Private Attributes | |
double | continuous_publishing_rate_ |
The rate of continuous publishing, in seconds. | |
std::vector < visualization_msgs::Marker > | grasp_markers_ |
The current set of visualization markers. | |
ros::Publisher | marker_pub_ |
Publisher for debug markers. | |
boost::mutex | mutex_ |
Mutex for access to list of grasp markers. | |
std::string | ns_append_ |
String to append to the namespace for each marker published by this publisher. | |
ros::NodeHandle | priv_nh_ |
Private node handle. | |
boost::thread * | publishing_thread_ |
Separate thread for continuous publishing. |
Publishes and keeps track of debug grasp markers.
Definition at line 49 of file grasp_marker_publisher.h.
Advertises the marker publishing topic with default options.
Definition at line 63 of file grasp_marker_publisher.cpp.
object_manipulator::GraspMarkerPublisher::GraspMarkerPublisher | ( | std::string | marker_out_name, |
std::string | ns_append, | ||
double | publishing_rate | ||
) |
Advertises the marker topic with aadvanced options.
Definition at line 69 of file grasp_marker_publisher.cpp.
Joins the publishing thread, if any.
Definition at line 75 of file grasp_marker_publisher.cpp.
unsigned int object_manipulator::GraspMarkerPublisher::addGraspMarker | ( | const geometry_msgs::PoseStamped & | marker_pose | ) |
Adds and publishes a marker with default color (blue). Returns the id of the new marker.
Definition at line 113 of file grasp_marker_publisher.cpp.
Removes and deletes all currently displayed markers.
Definition at line 101 of file grasp_marker_publisher.cpp.
void object_manipulator::GraspMarkerPublisher::colorGraspMarker | ( | unsigned int | marker_id, |
float | r, | ||
float | g, | ||
float | b | ||
) |
Sets the color of the grasp marker with the given id.
Definition at line 149 of file grasp_marker_publisher.cpp.
void object_manipulator::GraspMarkerPublisher::init | ( | std::string | marker_out_name, |
std::string | ns_append, | ||
double | publishing_rate | ||
) | [private] |
Operations common to all constructors, sets all the possible options.
Possible options:
marker_out_name | - the topic that markers are published on |
ns_append | - a suffix appended to the markers namespace |
publishing_rate | - the rate at which marker get re-published. Use a negative value to disable continuous re-publishing |
Definition at line 50 of file grasp_marker_publisher.cpp.
void object_manipulator::GraspMarkerPublisher::publishingThread | ( | ) | [private] |
Re-publishes all marker periodically.
Definition at line 85 of file grasp_marker_publisher.cpp.
void object_manipulator::GraspMarkerPublisher::setMarkerPose | ( | unsigned int | marker_id, |
const geometry_msgs::PoseStamped & | marker_pose | ||
) |
Sets the pose of the marker with the given id.
Definition at line 167 of file grasp_marker_publisher.cpp.
void object_manipulator::GraspMarkerPublisher::setNamespaceSuffix | ( | std::string | ns_append | ) | [inline] |
Sets the string to append to the namespace that the markers are published on.
Definition at line 96 of file grasp_marker_publisher.h.
The rate of continuous publishing, in seconds.
Definition at line 71 of file grasp_marker_publisher.h.
std::vector<visualization_msgs::Marker> object_manipulator::GraspMarkerPublisher::grasp_markers_ [private] |
The current set of visualization markers.
Definition at line 59 of file grasp_marker_publisher.h.
Publisher for debug markers.
Definition at line 56 of file grasp_marker_publisher.h.
boost::mutex object_manipulator::GraspMarkerPublisher::mutex_ [private] |
Mutex for access to list of grasp markers.
Definition at line 68 of file grasp_marker_publisher.h.
std::string object_manipulator::GraspMarkerPublisher::ns_append_ [private] |
String to append to the namespace for each marker published by this publisher.
Definition at line 62 of file grasp_marker_publisher.h.
Private node handle.
Definition at line 53 of file grasp_marker_publisher.h.
boost::thread* object_manipulator::GraspMarkerPublisher::publishing_thread_ [private] |
Separate thread for continuous publishing.
Definition at line 65 of file grasp_marker_publisher.h.