Classes | Public Member Functions | Private Attributes | List of all members
InteractiveMarkerInterface Class Reference

#include <interactive_marker_interface.h>

Classes

struct  ControlState
 
struct  GripperState
 
struct  MeshProperty
 
struct  UrdfProperty
 

Public Member Functions

void addHandMarker (visualization_msgs::InteractiveMarker &im, std::vector< UrdfProperty > urdf_vec)
 
void addSphereMarker (visualization_msgs::InteractiveMarker &im, double scale, std_msgs::ColorRGBA color)
 
void changeForceModeCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void changeForceModeCb1 (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void changeForceModeCb2 (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void changeMarkerForceMode (std::string mk_name, int im_mode)
 
void changeMarkerMoveMode (std::string mk_name, int im_mode)
 
void changeMarkerMoveMode (std::string mk_name, int im_mode, float mk_size)
 
void changeMarkerMoveMode (std::string mk_name, int im_mode, float mk_size, geometry_msgs::PoseStamped dist_pose)
 
void changeMarkerOperationModelMode (std::string mk_name)
 
void changeMoveArm (std::string m_name, int menu)
 
void changeMoveModeCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void changeMoveModeCb1 (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void changeMoveModeCb2 (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void ConstraintCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void ikmodeCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void IMSizeLargeCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void IMSizeMiddleCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void IMSizeSmallCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void initBodyMarkers (void)
 
void initControlMarkers (void)
 
void initHandler (void)
 
 InteractiveMarkerInterface ()
 
void loadMeshes (XmlRpc::XmlRpcValue val)
 
void loadMeshFromYaml (XmlRpc::XmlRpcValue val, std::string name, std::vector< MeshProperty > &mesh)
 
void loadUrdfFromYaml (XmlRpc::XmlRpcValue val, std::string name, std::vector< UrdfProperty > &mesh)
 
void lookAutomaticallyMenuCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
visualization_msgs::InteractiveMarker make6DofControlMarker (std::string name, geometry_msgs::PoseStamped &stamped, float scale, bool fixed_position, bool fixed_rotation)
 
visualization_msgs::InteractiveMarker makeBaseMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed)
 
void makeCenterSphere (visualization_msgs::InteractiveMarker &mk, double mk_size)
 
void makeIMVisible (visualization_msgs::InteractiveMarker &im)
 
void marker_menu_cb (const jsk_interactive_marker::MarkerMenuConstPtr &msg)
 
bool markers_del_cb (jsk_interactive_marker::MarkerSetPose::Request &req, jsk_interactive_marker::MarkerSetPose::Response &res)
 
bool markers_set_cb (jsk_interactive_marker::MarkerSetPose::Request &req, jsk_interactive_marker::MarkerSetPose::Response &res)
 
void modeCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void move_marker_cb (const geometry_msgs::PoseStampedConstPtr &msg)
 
void proc_feedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void proc_feedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int type)
 
void pub_marker_menu (std::string marker, int menu, int type)
 
void pub_marker_menu (std::string marker, int menu)
 
void pub_marker_menuCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu)
 
void pub_marker_menuCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu, int type)
 
void pub_marker_pose (std_msgs::Header header, geometry_msgs::Pose pose, std::string name, int type)
 
void pub_marker_tf (std_msgs::Header header, geometry_msgs::Pose pose)
 
bool reset_cb (jsk_interactive_marker::SetPose::Request &req, jsk_interactive_marker::SetPose::Response &res)
 
bool set_cb (jsk_interactive_marker::MarkerSetPose::Request &req, jsk_interactive_marker::MarkerSetPose::Response &res)
 
void setOriginCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, bool origin_hand)
 
void targetPointMenuCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void toggleIKModeCb (const std_msgs::EmptyConstPtr &msg)
 
void toggleStartIKCb (const std_msgs::EmptyConstPtr &msg)
 
void updateBase (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void updateFinger (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, std::string hand)
 
void updateHeadGoal (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void useTorsoCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void usingIKCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 

Private Attributes

std::string base_frame
 
ControlState control_state_
 
ros::ServiceClient dynamic_tf_publisher_client_
 
bool fix_marker
 
int h_mode_constrained
 
int h_mode_ikmode
 
interactive_markers::MenuHandler::EntryHandle h_mode_last
 
interactive_markers::MenuHandler::EntryHandle h_mode_last2
 
interactive_markers::MenuHandler::EntryHandle h_mode_last3
 
int h_mode_rightarm
 
std::string hand_type_
 
interactive_markers::MenuHandler::EntryHandle head_auto_look_handle_
 
geometry_msgs::PoseStamped head_goal_pose_
 
std::string head_link_frame_
 
std::string head_mesh_
 
interactive_markers::MenuHandler::EntryHandle head_target_handle_
 
std::list< visualization_msgs::InteractiveMarker > imlist
 
std::vector< MeshPropertylhand_mesh_
 
std::vector< UrdfPropertylhand_urdf_
 
std::string marker_name
 
interactive_markers::MenuHandler menu_base_
 
interactive_markers::MenuHandler menu_finger_l_
 
interactive_markers::MenuHandler menu_finger_r_
 
interactive_markers::MenuHandler menu_handler
 
interactive_markers::MenuHandler menu_handler1
 
interactive_markers::MenuHandler menu_handler2
 
interactive_markers::MenuHandler menu_handler_force
 
interactive_markers::MenuHandler menu_handler_force1
 
interactive_markers::MenuHandler menu_handler_force2
 
interactive_markers::MenuHandler menu_head_
 
interactive_markers::MenuHandler menu_head_target_
 
std::string move_base_frame
 
ros::NodeHandle nh_
 
ros::NodeHandle pnh_
 
ros::Publisher pub_
 
ros::Publisher pub_move_
 
ros::Publisher pub_update_
 
std::vector< MeshPropertyrhand_mesh_
 
std::vector< UrdfPropertyrhand_urdf_
 
interactive_markers::MenuHandler::EntryHandle rotation_nil_menu_
 
interactive_markers::MenuHandler::EntryHandle rotation_t_menu_
 
ros::ServiceServer serv_markers_del_
 
ros::ServiceServer serv_markers_set_
 
ros::ServiceServer serv_reset_
 
ros::ServiceServer serv_set_
 
std::shared_ptr< interactive_markers::InteractiveMarkerServerserver_
 
std::string server_name
 
interactive_markers::MenuHandler::EntryHandle start_ik_menu_
 
interactive_markers::MenuHandler::EntryHandle stop_ik_menu_
 
ros::Subscriber sub_marker_menu_
 
ros::Subscriber sub_marker_pose_
 
interactive_markers::MenuHandler::EntryHandle sub_menu_handle
 
interactive_markers::MenuHandler::EntryHandle sub_menu_handle2
 
interactive_markers::MenuHandler::EntryHandle sub_menu_handle_ik
 
ros::Subscriber sub_toggle_ik_mode_
 
ros::Subscriber sub_toggle_start_ik_
 
std::string target_frame
 
tf::TransformBroadcaster tfb_
 
int use_arm
 
bool use_body_marker_
 
bool use_center_sphere_
 
bool use_finger_marker_
 
interactive_markers::MenuHandler::EntryHandle use_fullbody_menu_
 
interactive_markers::MenuHandler::EntryHandle use_torso_menu_
 
interactive_markers::MenuHandler::EntryHandle use_torso_nil_menu_
 
interactive_markers::MenuHandler::EntryHandle use_torso_t_menu_
 

Detailed Description

Definition at line 27 of file interactive_marker_interface.h.

Constructor & Destructor Documentation

InteractiveMarkerInterface::InteractiveMarkerInterface ( )

Definition at line 1369 of file interactive_marker_interface.cpp.

Member Function Documentation

void InteractiveMarkerInterface::addHandMarker ( visualization_msgs::InteractiveMarker &  im,
std::vector< UrdfProperty urdf_vec 
)

Definition at line 1129 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::addSphereMarker ( visualization_msgs::InteractiveMarker &  im,
double  scale,
std_msgs::ColorRGBA  color 
)

Definition at line 1163 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeForceModeCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 230 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeForceModeCb1 ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 236 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeForceModeCb2 ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 242 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMarkerForceMode ( std::string  mk_name,
int  im_mode 
)

Definition at line 578 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMarkerMoveMode ( std::string  mk_name,
int  im_mode 
)

Definition at line 1202 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMarkerMoveMode ( std::string  mk_name,
int  im_mode,
float  mk_size 
)

Definition at line 1217 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMarkerMoveMode ( std::string  mk_name,
int  im_mode,
float  mk_size,
geometry_msgs::PoseStamped  dist_pose 
)

Definition at line 1224 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMarkerOperationModelMode ( std::string  mk_name)

Definition at line 1321 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMoveArm ( std::string  m_name,
int  menu 
)

Definition at line 399 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMoveModeCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 215 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMoveModeCb1 ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 220 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::changeMoveModeCb2 ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 225 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::ConstraintCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 287 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::ikmodeCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 442 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::IMSizeLargeCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 194 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::IMSizeMiddleCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 201 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::IMSizeSmallCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 208 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::initBodyMarkers ( void  )

Definition at line 723 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::initControlMarkers ( void  )

Definition at line 776 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::initHandler ( void  )

Definition at line 879 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::loadMeshes ( XmlRpc::XmlRpcValue  val)

Definition at line 1430 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::loadMeshFromYaml ( XmlRpc::XmlRpcValue  val,
std::string  name,
std::vector< MeshProperty > &  mesh 
)
void InteractiveMarkerInterface::loadUrdfFromYaml ( XmlRpc::XmlRpcValue  val,
std::string  name,
std::vector< UrdfProperty > &  mesh 
)

Definition at line 1435 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::lookAutomaticallyMenuCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 267 of file interactive_marker_interface.cpp.

visualization_msgs::InteractiveMarker InteractiveMarkerInterface::make6DofControlMarker ( std::string  name,
geometry_msgs::PoseStamped &  stamped,
float  scale,
bool  fixed_position,
bool  fixed_rotation 
)

Definition at line 30 of file interactive_marker_interface.cpp.

visualization_msgs::InteractiveMarker InteractiveMarkerInterface::makeBaseMarker ( const char *  name,
const geometry_msgs::PoseStamped &  stamped,
float  scale,
bool  fixed 
)

Definition at line 839 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::makeCenterSphere ( visualization_msgs::InteractiveMarker &  mk,
double  mk_size 
)

Definition at line 1182 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::makeIMVisible ( visualization_msgs::InteractiveMarker &  im)

Definition at line 1628 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::marker_menu_cb ( const jsk_interactive_marker::MarkerMenuConstPtr &  msg)

Definition at line 488 of file interactive_marker_interface.cpp.

bool InteractiveMarkerInterface::markers_del_cb ( jsk_interactive_marker::MarkerSetPose::Request &  req,
jsk_interactive_marker::MarkerSetPose::Response &  res 
)

Definition at line 1537 of file interactive_marker_interface.cpp.

bool InteractiveMarkerInterface::markers_set_cb ( jsk_interactive_marker::MarkerSetPose::Request &  req,
jsk_interactive_marker::MarkerSetPose::Response &  res 
)

Definition at line 1503 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::modeCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 375 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::move_marker_cb ( const geometry_msgs::PoseStampedConstPtr &  msg)

Definition at line 1556 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::proc_feedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 112 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::proc_feedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
int  type 
)

Definition at line 121 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::pub_marker_menu ( std::string  marker,
int  menu,
int  type 
)

Definition at line 182 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::pub_marker_menu ( std::string  marker,
int  menu 
)

Definition at line 190 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::pub_marker_menuCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
int  menu 
)

Definition at line 166 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::pub_marker_menuCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
int  menu,
int  type 
)

Definition at line 173 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::pub_marker_pose ( std_msgs::Header  header,
geometry_msgs::Pose  pose,
std::string  name,
int  type 
)

Definition at line 154 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::pub_marker_tf ( std_msgs::Header  header,
geometry_msgs::Pose  pose 
)

Definition at line 138 of file interactive_marker_interface.cpp.

bool InteractiveMarkerInterface::reset_cb ( jsk_interactive_marker::SetPose::Request &  req,
jsk_interactive_marker::SetPose::Response &  res 
)

Definition at line 1600 of file interactive_marker_interface.cpp.

bool InteractiveMarkerInterface::set_cb ( jsk_interactive_marker::MarkerSetPose::Request &  req,
jsk_interactive_marker::MarkerSetPose::Response &  res 
)

Definition at line 1566 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::setOriginCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
bool  origin_hand 
)

Definition at line 425 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::targetPointMenuCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 248 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::toggleIKModeCb ( const std_msgs::EmptyConstPtr &  msg)

Definition at line 466 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::toggleStartIKCb ( const std_msgs::EmptyConstPtr &  msg)

Definition at line 351 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::updateBase ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 536 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::updateFinger ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
std::string  hand 
)

Definition at line 546 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::updateHeadGoal ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 516 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::useTorsoCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 312 of file interactive_marker_interface.cpp.

void InteractiveMarkerInterface::usingIKCb ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 335 of file interactive_marker_interface.cpp.

Member Data Documentation

std::string InteractiveMarkerInterface::base_frame
private

Definition at line 196 of file interactive_marker_interface.h.

ControlState InteractiveMarkerInterface::control_state_
private

Definition at line 276 of file interactive_marker_interface.h.

ros::ServiceClient InteractiveMarkerInterface::dynamic_tf_publisher_client_
private

Definition at line 171 of file interactive_marker_interface.h.

bool InteractiveMarkerInterface::fix_marker
private

Definition at line 199 of file interactive_marker_interface.h.

int InteractiveMarkerInterface::h_mode_constrained
private

Definition at line 217 of file interactive_marker_interface.h.

int InteractiveMarkerInterface::h_mode_ikmode
private

Definition at line 218 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::h_mode_last
private

Definition at line 200 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::h_mode_last2
private

Definition at line 201 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::h_mode_last3
private

Definition at line 202 of file interactive_marker_interface.h.

int InteractiveMarkerInterface::h_mode_rightarm
private

Definition at line 216 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::hand_type_
private

Definition at line 280 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::head_auto_look_handle_
private

Definition at line 185 of file interactive_marker_interface.h.

geometry_msgs::PoseStamped InteractiveMarkerInterface::head_goal_pose_
private

Definition at line 278 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::head_link_frame_
private

Definition at line 282 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::head_mesh_
private

Definition at line 283 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::head_target_handle_
private

Definition at line 184 of file interactive_marker_interface.h.

std::list<visualization_msgs::InteractiveMarker> InteractiveMarkerInterface::imlist
private

Definition at line 223 of file interactive_marker_interface.h.

std::vector< MeshProperty > InteractiveMarkerInterface::lhand_mesh_
private

Definition at line 284 of file interactive_marker_interface.h.

std::vector< UrdfProperty > InteractiveMarkerInterface::lhand_urdf_
private

Definition at line 285 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::marker_name
private

Definition at line 194 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_base_
private

Definition at line 189 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_finger_l_
private

Definition at line 191 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_finger_r_
private

Definition at line 190 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_handler
private

Definition at line 173 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_handler1
private

Definition at line 174 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_handler2
private

Definition at line 175 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_handler_force
private

Definition at line 176 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_handler_force1
private

Definition at line 177 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_handler_force2
private

Definition at line 178 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_head_
private

Definition at line 183 of file interactive_marker_interface.h.

interactive_markers::MenuHandler InteractiveMarkerInterface::menu_head_target_
private

Definition at line 187 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::move_base_frame
private

Definition at line 197 of file interactive_marker_interface.h.

ros::NodeHandle InteractiveMarkerInterface::nh_
private

Definition at line 155 of file interactive_marker_interface.h.

ros::NodeHandle InteractiveMarkerInterface::pnh_
private

Definition at line 156 of file interactive_marker_interface.h.

ros::Publisher InteractiveMarkerInterface::pub_
private

Definition at line 158 of file interactive_marker_interface.h.

ros::Publisher InteractiveMarkerInterface::pub_move_
private

Definition at line 160 of file interactive_marker_interface.h.

ros::Publisher InteractiveMarkerInterface::pub_update_
private

Definition at line 159 of file interactive_marker_interface.h.

std::vector< MeshProperty > InteractiveMarkerInterface::rhand_mesh_
private

Definition at line 284 of file interactive_marker_interface.h.

std::vector< UrdfProperty > InteractiveMarkerInterface::rhand_urdf_
private

Definition at line 285 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::rotation_nil_menu_
private

Definition at line 205 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::rotation_t_menu_
private

Definition at line 204 of file interactive_marker_interface.h.

ros::ServiceServer InteractiveMarkerInterface::serv_markers_del_
private

Definition at line 164 of file interactive_marker_interface.h.

ros::ServiceServer InteractiveMarkerInterface::serv_markers_set_
private

Definition at line 163 of file interactive_marker_interface.h.

ros::ServiceServer InteractiveMarkerInterface::serv_reset_
private

Definition at line 161 of file interactive_marker_interface.h.

ros::ServiceServer InteractiveMarkerInterface::serv_set_
private

Definition at line 162 of file interactive_marker_interface.h.

std::shared_ptr<interactive_markers::InteractiveMarkerServer> InteractiveMarkerInterface::server_
private

Definition at line 157 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::server_name
private

Definition at line 195 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::start_ik_menu_
private

Definition at line 213 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::stop_ik_menu_
private

Definition at line 214 of file interactive_marker_interface.h.

ros::Subscriber InteractiveMarkerInterface::sub_marker_menu_
private

Definition at line 166 of file interactive_marker_interface.h.

ros::Subscriber InteractiveMarkerInterface::sub_marker_pose_
private

Definition at line 165 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::sub_menu_handle
private

Definition at line 179 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::sub_menu_handle2
private

Definition at line 180 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::sub_menu_handle_ik
private

Definition at line 181 of file interactive_marker_interface.h.

ros::Subscriber InteractiveMarkerInterface::sub_toggle_ik_mode_
private

Definition at line 168 of file interactive_marker_interface.h.

ros::Subscriber InteractiveMarkerInterface::sub_toggle_start_ik_
private

Definition at line 167 of file interactive_marker_interface.h.

std::string InteractiveMarkerInterface::target_frame
private

Definition at line 198 of file interactive_marker_interface.h.

tf::TransformBroadcaster InteractiveMarkerInterface::tfb_
private

Definition at line 170 of file interactive_marker_interface.h.

int InteractiveMarkerInterface::use_arm
private

Definition at line 219 of file interactive_marker_interface.h.

bool InteractiveMarkerInterface::use_body_marker_
private

Definition at line 272 of file interactive_marker_interface.h.

bool InteractiveMarkerInterface::use_center_sphere_
private

Definition at line 273 of file interactive_marker_interface.h.

bool InteractiveMarkerInterface::use_finger_marker_
private

Definition at line 271 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::use_fullbody_menu_
private

Definition at line 210 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::use_torso_menu_
private

Definition at line 207 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::use_torso_nil_menu_
private

Definition at line 209 of file interactive_marker_interface.h.

interactive_markers::MenuHandler::EntryHandle InteractiveMarkerInterface::use_torso_t_menu_
private

Definition at line 208 of file interactive_marker_interface.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