#include <parent_and_child_interactive_marker_server.h>

| Classes | |
| class | FeedbackSynthesizer | 
| Public Member Functions | |
| void | applyChanges () | 
| bool | erase (const std::string &name) | 
| bool | getMarkerPose (std::string target_name, geometry_msgs::PoseStamped &pose_stamped) | 
| bool | getMarkerPoseService (jsk_interactive_marker::GetTransformableMarkerPose::Request &req, jsk_interactive_marker::GetTransformableMarkerPose::Response &res) | 
| geometry_msgs::Pose | getRelativePose (geometry_msgs::PoseStamped parent_pose_stamped, geometry_msgs::PoseStamped child_pose_stamped) | 
| void | insert (const visualization_msgs::InteractiveMarker &int_marker) | 
| void | insert (const visualization_msgs::InteractiveMarker &int_marker, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB) | 
| ParentAndChildInteractiveMarkerServer (const std::string &topic_ns, const std::string &server_id="", bool spin_thread=false) | |
| void | parentFeedbackCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, std::string parent_topic_name) | 
| void | parentUpdateCb (const visualization_msgs::InteractiveMarkerUpdateConstPtr &update, std::string parent_topic_name) | 
| bool | registerAssociation (std::string parent_marker_name, std::string parent_topic_name, std::string child_marker_name, geometry_msgs::PoseStamped child_pose_stamped, geometry_msgs::PoseStamped parent_pose_stamped) | 
| bool | registerAssociationItself (std::string parent_marker_name, std::string parent_topic_name, std::string child_marker_name, geometry_msgs::PoseStamped child_pose_stamped) | 
| bool | registerAssociationWithOtherNode (std::string parent_marker_name, std::string parent_topic_name, std::string child_marker_name, geometry_msgs::PoseStamped child_pose_stamped) | 
| bool | removeParent (std::string child_marker_name) | 
| bool | removeParentService (jsk_interactive_marker::RemoveParentMarker::Request &req, jsk_interactive_marker::RemoveParentMarker::Response &res) | 
| void | renewPoseWithParent (std::map< std::string, ParentMarkerInformation >::iterator assoc_it_, geometry_msgs::Pose parent_pose, std_msgs::Header parent_header) | 
| void | selfFeedbackCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| bool | setCallback (const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB) | 
| bool | setParentService (jsk_interactive_marker::SetParentMarker::Request &req, jsk_interactive_marker::SetParentMarker::Response &res) | 
| Public Attributes | |
| std::map< std::string, ParentMarkerInformation > | association_list_ | 
| std::map< std::string, std::shared_ptr < FeedbackSynthesizer > > | callback_map_ | 
| ros::ServiceServer | get_marker_pose_srv_ | 
| ros::NodeHandle | n_ | 
| std::map< std::string, ros::Subscriber > | parent_feedback_subscribers_ | 
| std::map< std::string, int > | parent_subscriber_nums_ | 
| std::map< std::string, ros::Subscriber > | parent_update_subscribers_ | 
| ros::ServiceServer | remove_parent_srv_ | 
| ros::ServiceServer | set_parent_srv_ | 
| tf::TransformListener | tf_listener_ | 
| std::string | topic_server_name_ | 
Definition at line 31 of file parent_and_child_interactive_marker_server.h.
| jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::ParentAndChildInteractiveMarkerServer | ( | const std::string & | topic_ns, | 
| const std::string & | server_id = "", | ||
| bool | spin_thread = false | ||
| ) | 
Definition at line 5 of file parent_and_child_interactive_marker_server.cpp.
Reimplemented from interactive_markers::InteractiveMarkerServer.
Definition at line 220 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::erase | ( | const std::string & | name | ) | 
Reimplemented from interactive_markers::InteractiveMarkerServer.
Definition at line 268 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::getMarkerPose | ( | std::string | target_name, | 
| geometry_msgs::PoseStamped & | pose_stamped | ||
| ) | 
Definition at line 122 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::getMarkerPoseService | ( | jsk_interactive_marker::GetTransformableMarkerPose::Request & | req, | 
| jsk_interactive_marker::GetTransformableMarkerPose::Response & | res | ||
| ) | 
Definition at line 112 of file parent_and_child_interactive_marker_server.cpp.
| geometry_msgs::Pose jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::getRelativePose | ( | geometry_msgs::PoseStamped | parent_pose_stamped, | 
| geometry_msgs::PoseStamped | child_pose_stamped | ||
| ) | 
| void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::insert | ( | const visualization_msgs::InteractiveMarker & | int_marker | ) | 
Reimplemented from interactive_markers::InteractiveMarkerServer.
Definition at line 256 of file parent_and_child_interactive_marker_server.cpp.
| void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::insert | ( | const visualization_msgs::InteractiveMarker & | int_marker, | 
| FeedbackCallback | feedback_cb, | ||
| uint8_t | feedback_type = DEFAULT_FEEDBACK_CB | ||
| ) | 
Reimplemented from interactive_markers::InteractiveMarkerServer.
Definition at line 262 of file parent_and_child_interactive_marker_server.cpp.
| void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parentFeedbackCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback, | 
| std::string | parent_topic_name | ||
| ) | 
Definition at line 151 of file parent_and_child_interactive_marker_server.cpp.
| void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parentUpdateCb | ( | const visualization_msgs::InteractiveMarkerUpdateConstPtr & | update, | 
| std::string | parent_topic_name | ||
| ) | 
Definition at line 133 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::registerAssociation | ( | std::string | parent_marker_name, | 
| std::string | parent_topic_name, | ||
| std::string | child_marker_name, | ||
| geometry_msgs::PoseStamped | child_pose_stamped, | ||
| geometry_msgs::PoseStamped | parent_pose_stamped | ||
| ) | 
Definition at line 75 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::registerAssociationItself | ( | std::string | parent_marker_name, | 
| std::string | parent_topic_name, | ||
| std::string | child_marker_name, | ||
| geometry_msgs::PoseStamped | child_pose_stamped | ||
| ) | 
Definition at line 56 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::registerAssociationWithOtherNode | ( | std::string | parent_marker_name, | 
| std::string | parent_topic_name, | ||
| std::string | child_marker_name, | ||
| geometry_msgs::PoseStamped | child_pose_stamped | ||
| ) | 
Definition at line 62 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::removeParent | ( | std::string | child_marker_name | ) | 
Definition at line 98 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::removeParentService | ( | jsk_interactive_marker::RemoveParentMarker::Request & | req, | 
| jsk_interactive_marker::RemoveParentMarker::Response & | res | ||
| ) | 
Definition at line 94 of file parent_and_child_interactive_marker_server.cpp.
| void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::renewPoseWithParent | ( | std::map< std::string, ParentMarkerInformation >::iterator | assoc_it_, | 
| geometry_msgs::Pose | parent_pose, | ||
| std_msgs::Header | parent_header | ||
| ) | 
Definition at line 168 of file parent_and_child_interactive_marker_server.cpp.
| void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::selfFeedbackCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 177 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::setCallback | ( | const std::string & | name, | 
| FeedbackCallback | feedback_cb, | ||
| uint8_t | feedback_type = DEFAULT_FEEDBACK_CB | ||
| ) | 
Reimplemented from interactive_markers::InteractiveMarkerServer.
Definition at line 250 of file parent_and_child_interactive_marker_server.cpp.
| bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::setParentService | ( | jsk_interactive_marker::SetParentMarker::Request & | req, | 
| jsk_interactive_marker::SetParentMarker::Response & | res | ||
| ) | 
Definition at line 15 of file parent_and_child_interactive_marker_server.cpp.
| std::map<std::string, ParentMarkerInformation> jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::association_list_ | 
Definition at line 69 of file parent_and_child_interactive_marker_server.h.
| std::map<std::string, std::shared_ptr <FeedbackSynthesizer> > jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::callback_map_ | 
Definition at line 74 of file parent_and_child_interactive_marker_server.h.
| ros::ServiceServer jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::get_marker_pose_srv_ | 
Definition at line 65 of file parent_and_child_interactive_marker_server.h.
Definition at line 61 of file parent_and_child_interactive_marker_server.h.
| std::map<std::string, ros::Subscriber> jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parent_feedback_subscribers_ | 
Definition at line 73 of file parent_and_child_interactive_marker_server.h.
| std::map<std::string, int> jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parent_subscriber_nums_ | 
Definition at line 75 of file parent_and_child_interactive_marker_server.h.
| std::map<std::string, ros::Subscriber> jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parent_update_subscribers_ | 
Definition at line 72 of file parent_and_child_interactive_marker_server.h.
| ros::ServiceServer jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::remove_parent_srv_ | 
Definition at line 64 of file parent_and_child_interactive_marker_server.h.
Definition at line 63 of file parent_and_child_interactive_marker_server.h.
Definition at line 66 of file parent_and_child_interactive_marker_server.h.
Definition at line 67 of file parent_and_child_interactive_marker_server.h.