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

#include <transformable_interactive_server.h>

Public Member Functions

void addPose (geometry_msgs::Pose msg)
 
void addPoseRelative (geometry_msgs::Pose msg)
 
virtual void configCallback (InteractiveSettingConfig &config, uint32_t level)
 
void enableInteractiveManipulatorDisplay (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, const bool enable)
 
void eraseAllObject ()
 
void eraseFocusObject ()
 
void eraseObject (std::string name)
 
void focusInteractiveManipulatorDisplay ()
 
void focusObjectMarkerNamePublish ()
 
void focusPosePublish ()
 
void focusTextPublish ()
 
bool getColorService (jsk_interactive_marker::GetTransformableMarkerColor::Request &req, jsk_interactive_marker::GetTransformableMarkerColor::Response &res)
 
bool getDimensionsService (jsk_interactive_marker::GetMarkerDimensions::Request &req, jsk_interactive_marker::GetMarkerDimensions::Response &res)
 
bool getExistenceService (jsk_interactive_marker::GetTransformableMarkerExistence::Request &req, jsk_interactive_marker::GetTransformableMarkerExistence::Response &res)
 
bool getFocusService (jsk_interactive_marker::GetTransformableMarkerFocus::Request &req, jsk_interactive_marker::GetTransformableMarkerFocus::Response &res)
 
bool getPoseService (jsk_interactive_marker::GetTransformableMarkerPose::Request &req, jsk_interactive_marker::GetTransformableMarkerPose::Response &res, bool for_interactive_control)
 
bool getTypeService (jsk_interactive_marker::GetType::Request &req, jsk_interactive_marker::GetType::Response &res)
 
bool hideService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
void insertNewBox (std::string frame_id, std::string name, std::string description)
 
void insertNewCylinder (std::string frame_id, std::string name, std::string description)
 
void insertNewMesh (std::string frame_id, std::string name, std::string description, std::string mesh_resource, bool mesh_use_embedded_materials)
 
void insertNewObject (TransformableObject *tobject, std::string name)
 
void insertNewTorus (std::string frame_id, std::string name, std::string description)
 
void processFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void publishMarkerDimensions ()
 
bool requestMarkerOperateService (jsk_rviz_plugins::RequestMarkerOperate::Request &req, jsk_rviz_plugins::RequestMarkerOperate::Response &res)
 
void run ()
 
void setColor (std_msgs::ColorRGBA msg)
 
bool setColorService (jsk_interactive_marker::SetTransformableMarkerColor::Request &req, jsk_interactive_marker::SetTransformableMarkerColor::Response &res)
 
void setControlRelativePose (geometry_msgs::Pose msg)
 
bool setDimensionsService (jsk_interactive_marker::SetMarkerDimensions::Request &req, jsk_interactive_marker::SetMarkerDimensions::Response &res)
 
bool setFocusService (jsk_interactive_marker::SetTransformableMarkerFocus::Request &req, jsk_interactive_marker::SetTransformableMarkerFocus::Response &res)
 
void SetInitialInteractiveMarkerConfig (TransformableObject *tobject)
 
void setPose (const geometry_msgs::PoseStampedConstPtr &msg_ptr, bool for_interactive_control=false)
 
bool setPoseService (jsk_interactive_marker::SetTransformableMarkerPose::Request &req, jsk_interactive_marker::SetTransformableMarkerPose::Response &res, bool for_interactive_control)
 
bool setPoseWithTfTransformation (TransformableObject *tobject, geometry_msgs::PoseStamped pose_stamped, bool for_interactive_control=false)
 
void setRadius (std_msgs::Float32 msg)
 
void setSmallRadius (std_msgs::Float32 msg)
 
void setX (std_msgs::Float32 msg)
 
void setY (std_msgs::Float32 msg)
 
void setZ (std_msgs::Float32 msg)
 
bool showService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
void tfTimerCallback (const ros::TimerEvent &)
 
 TransformableInteractiveServer ()
 
void updateTransformableObject (TransformableObject *tobject)
 
 ~TransformableInteractiveServer ()
 

Public Attributes

ros::Subscriber addpose_relative_sub_
 
ros::Subscriber addpose_sub_
 
jsk_interactive_marker::InteractiveSettingConfig config_
 
std::shared_ptr< dynamic_reconfigure::Server< InteractiveSettingConfig > > config_srv_
 
ros::Publisher focus_name_text_pub_
 
std::string focus_object_marker_name_
 
ros::Publisher focus_object_marker_name_pub_
 
ros::Publisher focus_pose_text_pub_
 
ros::ServiceServer get_color_srv_
 
ros::ServiceServer get_control_pose_srv_
 
ros::ServiceServer get_dimensions_srv
 
ros::ServiceServer get_exist_srv_
 
ros::ServiceServer get_focus_srv_
 
ros::ServiceServer get_pose_srv_
 
ros::ServiceServer get_type_srv_
 
ros::ServiceServer hide_srv_
 
int interactive_manipulator_orientation_
 
ros::Publisher marker_dimensions_pub_
 
boost::mutex mutex_
 
ros::NodeHandlen_
 
ros::Publisher pose_pub_
 
ros::Publisher pose_with_name_pub_
 
ros::ServiceServer request_marker_operate_srv_
 
interactive_markers::InteractiveMarkerServerserver_
 
ros::ServiceServer set_color_srv_
 
ros::ServiceServer set_control_pose_srv_
 
ros::ServiceServer set_dimensions_srv
 
ros::ServiceServer set_focus_srv_
 
ros::Subscriber set_h_sub_
 
ros::ServiceServer set_pose_srv_
 
ros::Subscriber set_r_sub_
 
ros::Subscriber set_sm_r_sub_
 
ros::Subscriber set_x_sub_
 
ros::Subscriber set_y_sub_
 
ros::Subscriber set_z_sub_
 
ros::Subscriber setcolor_sub_
 
ros::Subscriber setcontrol_relative_sub_
 
ros::Subscriber setcontrolpose_sub_
 
ros::Subscriber setpose_sub_
 
ros::Subscriber setrad_sub_
 
ros::ServiceServer show_srv_
 
bool strict_tf_
 
std::shared_ptr< tf::TransformListenertf_listener_
 
ros::Timer tf_timer
 
int torus_udiv_
 
int torus_vdiv_
 
map< string, TransformableObject * > transformable_objects_map_
 
std::shared_ptr< YamlMenuHandleryaml_menu_handler_ptr_
 

Detailed Description

Definition at line 37 of file transformable_interactive_server.h.

Constructor & Destructor Documentation

TransformableInteractiveServer::TransformableInteractiveServer ( )

Definition at line 6 of file transformable_interactive_server.cpp.

TransformableInteractiveServer::~TransformableInteractiveServer ( )

Definition at line 84 of file transformable_interactive_server.cpp.

Member Function Documentation

void TransformableInteractiveServer::addPose ( geometry_msgs::Pose  msg)

Definition at line 488 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::addPoseRelative ( geometry_msgs::Pose  msg)

Definition at line 495 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::configCallback ( InteractiveSettingConfig &  config,
uint32_t  level 
)
virtual

Definition at line 92 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::enableInteractiveManipulatorDisplay ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
const bool  enable 
)

Definition at line 517 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::eraseAllObject ( )

Definition at line 661 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::eraseFocusObject ( )

Definition at line 668 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::eraseObject ( std::string  name)

Definition at line 647 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::focusInteractiveManipulatorDisplay ( )

Definition at line 525 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::focusObjectMarkerNamePublish ( )

Definition at line 591 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::focusPosePublish ( )

Definition at line 562 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::focusTextPublish ( )

Definition at line 542 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::getColorService ( jsk_interactive_marker::GetTransformableMarkerColor::Request &  req,
jsk_interactive_marker::GetTransformableMarkerColor::Response &  res 
)

Definition at line 253 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::getDimensionsService ( jsk_interactive_marker::GetMarkerDimensions::Request &  req,
jsk_interactive_marker::GetMarkerDimensions::Response &  res 
)

Definition at line 347 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::getExistenceService ( jsk_interactive_marker::GetTransformableMarkerExistence::Request &  req,
jsk_interactive_marker::GetTransformableMarkerExistence::Response &  res 
)

Definition at line 312 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::getFocusService ( jsk_interactive_marker::GetTransformableMarkerFocus::Request &  req,
jsk_interactive_marker::GetTransformableMarkerFocus::Response &  res 
)

Definition at line 282 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::getPoseService ( jsk_interactive_marker::GetTransformableMarkerPose::Request &  req,
jsk_interactive_marker::GetTransformableMarkerPose::Response &  res,
bool  for_interactive_control 
)

Definition at line 213 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::getTypeService ( jsk_interactive_marker::GetType::Request &  req,
jsk_interactive_marker::GetType::Response &  res 
)

Definition at line 297 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::hideService ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 372 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::insertNewBox ( std::string  frame_id,
std::string  name,
std::string  description 
)

Definition at line 597 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::insertNewCylinder ( std::string  frame_id,
std::string  name,
std::string  description 
)

Definition at line 603 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::insertNewMesh ( std::string  frame_id,
std::string  name,
std::string  description,
std::string  mesh_resource,
bool  mesh_use_embedded_materials 
)

Definition at line 615 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::insertNewObject ( TransformableObject tobject,
std::string  name 
)

Definition at line 621 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::insertNewTorus ( std::string  frame_id,
std::string  name,
std::string  description 
)

Definition at line 609 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::processFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 105 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::publishMarkerDimensions ( )

Definition at line 397 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::requestMarkerOperateService ( jsk_rviz_plugins::RequestMarkerOperate::Request &  req,
jsk_rviz_plugins::RequestMarkerOperate::Response &  res 
)

Definition at line 417 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::run ( )

Definition at line 723 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setColor ( std_msgs::ColorRGBA  msg)

Definition at line 136 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::setColorService ( jsk_interactive_marker::SetTransformableMarkerColor::Request &  req,
jsk_interactive_marker::SetTransformableMarkerColor::Response &  res 
)

Definition at line 267 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setControlRelativePose ( geometry_msgs::Pose  msg)

Definition at line 502 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::setDimensionsService ( jsk_interactive_marker::SetMarkerDimensions::Request &  req,
jsk_interactive_marker::SetMarkerDimensions::Response &  res 
)

Definition at line 322 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::setFocusService ( jsk_interactive_marker::SetTransformableMarkerFocus::Request &  req,
jsk_interactive_marker::SetTransformableMarkerFocus::Response &  res 
)

Definition at line 288 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::SetInitialInteractiveMarkerConfig ( TransformableObject tobject)

Definition at line 636 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setPose ( const geometry_msgs::PoseStampedConstPtr &  msg_ptr,
bool  for_interactive_control = false 
)

Definition at line 202 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::setPoseService ( jsk_interactive_marker::SetTransformableMarkerPose::Request &  req,
jsk_interactive_marker::SetTransformableMarkerPose::Response &  res,
bool  for_interactive_control 
)

Definition at line 231 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::setPoseWithTfTransformation ( TransformableObject tobject,
geometry_msgs::PoseStamped  pose_stamped,
bool  for_interactive_control = false 
)

Definition at line 680 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setRadius ( std_msgs::Float32  msg)

Definition at line 144 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setSmallRadius ( std_msgs::Float32  msg)

Definition at line 154 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setX ( std_msgs::Float32  msg)

Definition at line 164 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setY ( std_msgs::Float32  msg)

Definition at line 174 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::setZ ( std_msgs::Float32  msg)

Definition at line 184 of file transformable_interactive_server.cpp.

bool TransformableInteractiveServer::showService ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)

Definition at line 385 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::tfTimerCallback ( const ros::TimerEvent )

Definition at line 673 of file transformable_interactive_server.cpp.

void TransformableInteractiveServer::updateTransformableObject ( TransformableObject tobject)

Definition at line 194 of file transformable_interactive_server.cpp.

Member Data Documentation

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::addpose_relative_sub_

Definition at line 110 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::addpose_sub_

Definition at line 109 of file transformable_interactive_server.h.

jsk_interactive_marker::InteractiveSettingConfig jsk_interactive_marker::TransformableInteractiveServer::config_

Definition at line 151 of file transformable_interactive_server.h.

std::shared_ptr<dynamic_reconfigure::Server<InteractiveSettingConfig> > jsk_interactive_marker::TransformableInteractiveServer::config_srv_

Definition at line 138 of file transformable_interactive_server.h.

ros::Publisher jsk_interactive_marker::TransformableInteractiveServer::focus_name_text_pub_

Definition at line 141 of file transformable_interactive_server.h.

std::string jsk_interactive_marker::TransformableInteractiveServer::focus_object_marker_name_

Definition at line 101 of file transformable_interactive_server.h.

ros::Publisher jsk_interactive_marker::TransformableInteractiveServer::focus_object_marker_name_pub_

Definition at line 143 of file transformable_interactive_server.h.

ros::Publisher jsk_interactive_marker::TransformableInteractiveServer::focus_pose_text_pub_

Definition at line 142 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_color_srv_

Definition at line 127 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_control_pose_srv_

Definition at line 124 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_dimensions_srv

Definition at line 134 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_exist_srv_

Definition at line 132 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_focus_srv_

Definition at line 129 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_pose_srv_

Definition at line 123 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::get_type_srv_

Definition at line 131 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::hide_srv_

Definition at line 121 of file transformable_interactive_server.h.

int jsk_interactive_marker::TransformableInteractiveServer::interactive_manipulator_orientation_

Definition at line 153 of file transformable_interactive_server.h.

ros::Publisher jsk_interactive_marker::TransformableInteractiveServer::marker_dimensions_pub_

Definition at line 135 of file transformable_interactive_server.h.

boost::mutex jsk_interactive_marker::TransformableInteractiveServer::mutex_

Definition at line 104 of file transformable_interactive_server.h.

ros::NodeHandle* jsk_interactive_marker::TransformableInteractiveServer::n_

Definition at line 102 of file transformable_interactive_server.h.

ros::Publisher jsk_interactive_marker::TransformableInteractiveServer::pose_pub_

Definition at line 144 of file transformable_interactive_server.h.

ros::Publisher jsk_interactive_marker::TransformableInteractiveServer::pose_with_name_pub_

Definition at line 145 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::request_marker_operate_srv_

Definition at line 136 of file transformable_interactive_server.h.

interactive_markers::InteractiveMarkerServer* jsk_interactive_marker::TransformableInteractiveServer::server_

Definition at line 146 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::set_color_srv_

Definition at line 128 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::set_control_pose_srv_

Definition at line 126 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::set_dimensions_srv

Definition at line 133 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::set_focus_srv_

Definition at line 130 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::set_h_sub_

Definition at line 116 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::set_pose_srv_

Definition at line 125 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::set_r_sub_

Definition at line 114 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::set_sm_r_sub_

Definition at line 115 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::set_x_sub_

Definition at line 117 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::set_y_sub_

Definition at line 118 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::set_z_sub_

Definition at line 119 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::setcolor_sub_

Definition at line 106 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::setcontrol_relative_sub_

Definition at line 112 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::setcontrolpose_sub_

Definition at line 108 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::setpose_sub_

Definition at line 107 of file transformable_interactive_server.h.

ros::Subscriber jsk_interactive_marker::TransformableInteractiveServer::setrad_sub_

Definition at line 140 of file transformable_interactive_server.h.

ros::ServiceServer jsk_interactive_marker::TransformableInteractiveServer::show_srv_

Definition at line 122 of file transformable_interactive_server.h.

bool jsk_interactive_marker::TransformableInteractiveServer::strict_tf_

Definition at line 152 of file transformable_interactive_server.h.

std::shared_ptr<tf::TransformListener> jsk_interactive_marker::TransformableInteractiveServer::tf_listener_

Definition at line 148 of file transformable_interactive_server.h.

ros::Timer jsk_interactive_marker::TransformableInteractiveServer::tf_timer

Definition at line 154 of file transformable_interactive_server.h.

int jsk_interactive_marker::TransformableInteractiveServer::torus_udiv_

Definition at line 149 of file transformable_interactive_server.h.

int jsk_interactive_marker::TransformableInteractiveServer::torus_vdiv_

Definition at line 150 of file transformable_interactive_server.h.

map<string, TransformableObject*> jsk_interactive_marker::TransformableInteractiveServer::transformable_objects_map_

Definition at line 147 of file transformable_interactive_server.h.

std::shared_ptr<YamlMenuHandler> jsk_interactive_marker::TransformableInteractiveServer::yaml_menu_handler_ptr_

Definition at line 155 of file transformable_interactive_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