Classes | Public Member Functions | Public Attributes
jsk_interactive_marker::ParentAndChildInteractiveMarkerServer Class Reference

#include <parent_and_child_interactive_marker_server.h>

Inheritance diagram for jsk_interactive_marker::ParentAndChildInteractiveMarkerServer:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

Definition at line 31 of file parent_and_child_interactive_marker_server.h.


Constructor & Destructor Documentation

jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::ParentAndChildInteractiveMarkerServer ( const std::string topic_ns,
const std::string server_id = "",
bool  spin_thread = false 
)

Member Function Documentation

bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::getMarkerPose ( std::string  target_name,
geometry_msgs::PoseStamped &  pose_stamped 
)
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::getMarkerPoseService ( jsk_interactive_marker::GetTransformableMarkerPose::Request &  req,
jsk_interactive_marker::GetTransformableMarkerPose::Response &  res 
)
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)
void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::insert ( const visualization_msgs::InteractiveMarker &  int_marker,
FeedbackCallback  feedback_cb,
uint8_t  feedback_type = DEFAULT_FEEDBACK_CB 
)
void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parentFeedbackCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
std::string  parent_topic_name 
)
void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::parentUpdateCb ( const visualization_msgs::InteractiveMarkerUpdateConstPtr &  update,
std::string  parent_topic_name 
)
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 
)
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 
)
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 
)
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::removeParentService ( jsk_interactive_marker::RemoveParentMarker::Request &  req,
jsk_interactive_marker::RemoveParentMarker::Response &  res 
)
void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::selfFeedbackCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::setParentService ( jsk_interactive_marker::SetParentMarker::Request &  req,
jsk_interactive_marker::SetParentMarker::Response &  res 
)

Member Data Documentation

Definition at line 69 of file parent_and_child_interactive_marker_server.h.

Definition at line 74 of file parent_and_child_interactive_marker_server.h.

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.

Definition at line 73 of file parent_and_child_interactive_marker_server.h.

Definition at line 75 of file parent_and_child_interactive_marker_server.h.

Definition at line 72 of file parent_and_child_interactive_marker_server.h.

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.


The documentation for this class was generated from the following files:


jsk_interactive_marker
Author(s): furuta
autogenerated on Wed May 1 2019 02:40:31