Classes | Public Member Functions | Public Attributes | List of all members
jsk_interactive_marker::ParentAndChildInteractiveMarkerServer Class Reference

#include <parent_and_child_interactive_marker_server.h>

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

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 Member Functions inherited from interactive_markers::InteractiveMarkerServer
INTERACTIVE_MARKERS_PUBLIC void applyChanges ()
 
INTERACTIVE_MARKERS_PUBLIC void clear ()
 
INTERACTIVE_MARKERS_PUBLIC bool empty () const
 
INTERACTIVE_MARKERS_PUBLIC bool erase (const std::string &name)
 
INTERACTIVE_MARKERS_PUBLIC bool get (std::string name, visualization_msgs::InteractiveMarker &int_marker) const
 
INTERACTIVE_MARKERS_PUBLIC void insert (const visualization_msgs::InteractiveMarker &int_marker)
 
INTERACTIVE_MARKERS_PUBLIC void insert (const visualization_msgs::InteractiveMarker &int_marker, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
 
INTERACTIVE_MARKERS_PUBLIC InteractiveMarkerServer (const std::string &topic_ns, const std::string &server_id="", bool spin_thread=false)
 
INTERACTIVE_MARKERS_PUBLIC bool setCallback (const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
 
INTERACTIVE_MARKERS_PUBLIC bool setPose (const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
 
INTERACTIVE_MARKERS_PUBLIC std::size_t size () const
 
INTERACTIVE_MARKERS_PUBLIC ~InteractiveMarkerServer ()
 

Public Attributes

std::map< std::string, ParentMarkerInformationassociation_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::Subscriberparent_feedback_subscribers_
 
std::map< std::string, int > parent_subscriber_nums_
 
std::map< std::string, ros::Subscriberparent_update_subscribers_
 
ros::ServiceServer remove_parent_srv_
 
ros::ServiceServer set_parent_srv_
 
tf::TransformListener tf_listener_
 
std::string topic_server_name_
 

Additional Inherited Members

- Public Types inherited from interactive_markers::InteractiveMarkerServer
typedef boost::function< void(const FeedbackConstPtr &) > FeedbackCallback
 
typedef visualization_msgs::InteractiveMarkerFeedbackConstPtr FeedbackConstPtr
 
- Static Public Attributes inherited from interactive_markers::InteractiveMarkerServer
static const uint8_t DEFAULT_FEEDBACK_CB
 

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

void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::applyChanges ( )
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::erase ( const std::string name)
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::removeParent ( std::string  child_marker_name)
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::removeParentService ( jsk_interactive_marker::RemoveParentMarker::Request &  req,
jsk_interactive_marker::RemoveParentMarker::Response &  res 
)
void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::renewPoseWithParent ( std::map< std::string, ParentMarkerInformation >::iterator  assoc_it_,
geometry_msgs::Pose  parent_pose,
std_msgs::Header  parent_header 
)
void jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::selfFeedbackCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::setCallback ( const std::string name,
FeedbackCallback  feedback_cb,
uint8_t  feedback_type = DEFAULT_FEEDBACK_CB 
)
bool jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::setParentService ( jsk_interactive_marker::SetParentMarker::Request &  req,
jsk_interactive_marker::SetParentMarker::Response &  res 
)

Member Data Documentation

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.

ros::NodeHandle jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::n_

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.

ros::ServiceServer jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::set_parent_srv_

Definition at line 63 of file parent_and_child_interactive_marker_server.h.

tf::TransformListener jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::tf_listener_

Definition at line 66 of file parent_and_child_interactive_marker_server.h.

std::string jsk_interactive_marker::ParentAndChildInteractiveMarkerServer::topic_server_name_

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 Sat Mar 20 2021 03:03:33