Public Types | |
typedef visualization_msgs::InteractiveMarkerInitConstPtr | InitConstPtr |
typedef visualization_msgs::InteractiveMarkerUpdateConstPtr | UpdateConstPtr |
typedef visualization_msgs::InteractiveMarkerUpdatePtr | UpdatePtr |
Public Member Functions | |
bool | getInit (interactive_marker_proxy::GetInit::Request &request, interactive_marker_proxy::GetInit::Response &response) |
void | initCb (const InitConstPtr &init_msg) |
Proxy (std::string target_frame, std::string topic_ns) | |
void | resetCb (const std::string &server_id) |
void | statusCb (InteractiveMarkerClient::StatusT status, const std::string &server_id, const std::string &status_text) |
void | timerCb (const ros::TimerEvent &) |
void | updateCb (const UpdateConstPtr &up_msg) |
Public Attributes | |
interactive_markers::InteractiveMarkerClient | client_ |
std::map< std::string, visualization_msgs::InteractiveMarker > | int_markers_ |
ros::NodeHandle | nh_ |
ros::Publisher | pub_ |
ros::ServiceServer | service_ |
std::map< std::string, std::string > | status_text_ |
std::string | target_frame_ |
tf::TransformListener | tf_ |
ros::Timer | timer_ |
std::string | topic_ns_ |
typedef visualization_msgs::InteractiveMarkerInitConstPtr Proxy::InitConstPtr |
typedef visualization_msgs::InteractiveMarkerUpdateConstPtr Proxy::UpdateConstPtr |
typedef visualization_msgs::InteractiveMarkerUpdatePtr Proxy::UpdatePtr |
Proxy::Proxy | ( | std::string | target_frame, |
std::string | topic_ns | ||
) | [inline] |
bool Proxy::getInit | ( | interactive_marker_proxy::GetInit::Request & | request, |
interactive_marker_proxy::GetInit::Response & | response | ||
) | [inline] |
void Proxy::initCb | ( | const InitConstPtr & | init_msg | ) | [inline] |
void Proxy::resetCb | ( | const std::string & | server_id | ) | [inline] |
void Proxy::statusCb | ( | InteractiveMarkerClient::StatusT | status, |
const std::string & | server_id, | ||
const std::string & | status_text | ||
) | [inline] |
void Proxy::timerCb | ( | const ros::TimerEvent & | ) | [inline] |
void Proxy::updateCb | ( | const UpdateConstPtr & | up_msg | ) | [inline] |
std::map<std::string, visualization_msgs::InteractiveMarker> Proxy::int_markers_ |
std::map<std::string, std::string> Proxy::status_text_ |
std::string Proxy::target_frame_ |
std::string Proxy::topic_ns_ |