#include <urdf_model_marker.h>
| Classes | |
| struct | graspPoint | 
| struct | linkProperty | 
| Public Member Functions | |
| void | addChildLinkNames (LinkConstSharedPtr link, bool root, bool init) | 
| void | addChildLinkNames (LinkConstSharedPtr link, bool root, bool init, bool use_color, int color_index) | 
| void | addGraspPointControl (visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_) | 
| void | addInvisibleMeshMarkerControl (visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, const std_msgs::ColorRGBA &color) | 
| void | addMoveMarkerControl (visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, bool root) | 
| void | callPublishTf () | 
| void | callSetDynamicTf (string parent_frame_id, string frame_id, geometry_msgs::Transform transform) | 
| void | getJointState () | 
| void | getJointState (LinkConstSharedPtr link) | 
| geometry_msgs::PoseStamped | getOriginPoseStamped () | 
| geometry_msgs::Pose | getRootPose (geometry_msgs::Pose pose) | 
| void | graspPoint_feedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string link_name) | 
| void | graspPointCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | hideAllMarkerCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | hideMarkerCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | hideModelMarkerCB (const std_msgs::EmptyConstPtr &msg) | 
| void | jointMoveCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| bool | lockJointStates (std_srvs::EmptyRequest &req, std_srvs::EmptyRequest &res) | 
| int | main (string file) | 
| visualization_msgs::InteractiveMarkerControl | makeBoxMarkerControl (const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color) | 
| visualization_msgs::InteractiveMarkerControl | makeCylinderMarkerControl (const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color) | 
| visualization_msgs::InteractiveMarkerControl | makeMeshMarkerControl (const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color, bool use_color) | 
| visualization_msgs::InteractiveMarkerControl | makeMeshMarkerControl (const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale) | 
| visualization_msgs::InteractiveMarkerControl | makeMeshMarkerControl (const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color) | 
| visualization_msgs::InteractiveMarkerControl | makeSphereMarkerControl (const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color) | 
| void | moveCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | proc_feedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string parent_frame_id, string frame_id) | 
| void | publishBasePose (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | publishBasePose (geometry_msgs::Pose pose, std_msgs::Header header) | 
| void | publishJointState (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | publishJointState () | 
| void | publishMarkerMenu (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu) | 
| void | publishMarkerPose (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | publishMarkerPose (geometry_msgs::Pose pose, std_msgs::Header header, std::string marker_name) | 
| void | publishMoveObject (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | registrationCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | republishJointState (sensor_msgs::JointState js) | 
| void | resetBaseCB () | 
| void | resetBaseMarkerCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | resetBaseMsgCB (const std_msgs::EmptyConstPtr &msg) | 
| void | resetJointStatesCB (const sensor_msgs::JointStateConstPtr &msg, bool update_root) | 
| void | resetMarkerCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | resetRobotBase () | 
| void | resetRootForVisualization () | 
| void | setJointAngle (LinkConstSharedPtr link, double joint_angle) | 
| void | setJointState (LinkConstSharedPtr link, const sensor_msgs::JointStateConstPtr &js) | 
| void | setOriginalPose (LinkConstSharedPtr link) | 
| void | setPoseCB () | 
| void | setPoseCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | setRootPose (geometry_msgs::PoseStamped ps) | 
| void | setRootPoseCB (const geometry_msgs::PoseStampedConstPtr &msg) | 
| void | setUrdfCB (const std_msgs::StringConstPtr &msg) | 
| void | showModelMarkerCB (const std_msgs::EmptyConstPtr &msg) | 
| bool | unlockJointStates (std_srvs::EmptyRequest &req, std_srvs::EmptyRequest &res) | 
| void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) | 
| UrdfModelMarker (string file, std::shared_ptr< interactive_markers::InteractiveMarkerServer > server) | |
| UrdfModelMarker (string model_name, string model_description, string model_file, string frame_id, geometry_msgs::PoseStamped root_pose, geometry_msgs::Pose root_offset, double scale_factor, string mode, bool robot_mode, bool registration, vector< string > fixed_link, bool use_robot_description, bool use_visible_color, map< string, double > initial_pose_map, int index, std::shared_ptr< interactive_markers::InteractiveMarkerServer > server) | |
| UrdfModelMarker () | |
| Protected Attributes | |
| std::string | base_frame | 
| std::shared_ptr < diagnostic_updater::Updater > | diagnostic_updater_ | 
| jsk_topic_tools::TimeAccumulator | dynamic_tf_check_time_acc_ | 
| ros::ServiceClient | dynamic_tf_publisher_client | 
| ros::ServiceClient | dynamic_tf_publisher_publish_tf_client | 
| vector< string > | fixed_link_ | 
| geometry_msgs::Pose | fixed_link_offset_ | 
| std::string | frame_id_ | 
| ros::Subscriber | hide_marker_ | 
| int | index_ | 
| ros::Time | init_stamp_ | 
| map< string, double > | initial_pose_map_ | 
| bool | is_joint_states_locked_ | 
| sensor_msgs::JointState | joint_state_ | 
| sensor_msgs::JointState | joint_state_origin_ | 
| boost::mutex | joint_states_mutex_ | 
| map< string, linkProperty > | linkMarkerMap | 
| string | mode_ | 
| ModelInterfaceSharedPtr | model | 
| std::string | model_description_ | 
| std::string | model_file_ | 
| interactive_markers::MenuHandler | model_menu_ | 
| std::string | model_name_ | 
| std::string | move_base_frame | 
| ros::NodeHandle | nh_ | 
| ros::NodeHandle | pnh_ | 
| ros::Publisher | pub_ | 
| ros::Publisher | pub_base_pose_ | 
| ros::Publisher | pub_joint_state_ | 
| ros::Publisher | pub_move_ | 
| ros::Publisher | pub_move_model_ | 
| ros::Publisher | pub_move_object_ | 
| ros::Publisher | pub_selected_ | 
| ros::Publisher | pub_selected_index_ | 
| bool | registration_ | 
| jsk_topic_tools::TimeAccumulator | reset_joint_states_check_time_acc_ | 
| bool | robot_mode_ | 
| geometry_msgs::Pose | root_offset_ | 
| geometry_msgs::Pose | root_pose_ | 
| geometry_msgs::Pose | root_pose_origin_ | 
| double | scale_factor_ | 
| ros::ServiceServer | serv_lock_joint_states_ | 
| ros::ServiceServer | serv_markers_del_ | 
| ros::ServiceServer | serv_markers_set_ | 
| ros::ServiceServer | serv_reset_ | 
| ros::ServiceServer | serv_set_ | 
| ros::ServiceServer | serv_unlock_joint_states_ | 
| std::shared_ptr < interactive_markers::InteractiveMarkerServer > | server_ | 
| std::string | server_name | 
| ros::Subscriber | show_marker_ | 
| ros::Subscriber | sub_reset_joints_ | 
| ros::Subscriber | sub_reset_joints_and_root_ | 
| ros::Subscriber | sub_set_root_pose_ | 
| ros::Subscriber | sub_set_urdf_ | 
| std::string | target_frame | 
| std::string | tf_prefix_ | 
| tf::TransformBroadcaster | tfb_ | 
| tf::TransformListener | tfl_ | 
| bool | use_dynamic_tf_ | 
| bool | use_robot_description_ | 
| bool | use_visible_color_ | 
Definition at line 54 of file urdf_model_marker.h.
| UrdfModelMarker::UrdfModelMarker | ( | string | file, | 
| std::shared_ptr< interactive_markers::InteractiveMarkerServer > | server | ||
| ) | 
| UrdfModelMarker::UrdfModelMarker | ( | string | model_name, | 
| string | model_description, | ||
| string | model_file, | ||
| string | frame_id, | ||
| geometry_msgs::PoseStamped | root_pose, | ||
| geometry_msgs::Pose | root_offset, | ||
| double | scale_factor, | ||
| string | mode, | ||
| bool | robot_mode, | ||
| bool | registration, | ||
| vector< string > | fixed_link, | ||
| bool | use_robot_description, | ||
| bool | use_visible_color, | ||
| map< string, double > | initial_pose_map, | ||
| int | index, | ||
| std::shared_ptr< interactive_markers::InteractiveMarkerServer > | server | ||
| ) | 
Definition at line 1180 of file urdf_model_marker.cpp.
Definition at line 1177 of file urdf_model_marker.cpp.
| void UrdfModelMarker::addChildLinkNames | ( | LinkConstSharedPtr | link, | 
| bool | root, | ||
| bool | init | ||
| ) | 
Definition at line 912 of file urdf_model_marker.cpp.
| void UrdfModelMarker::addChildLinkNames | ( | LinkConstSharedPtr | link, | 
| bool | root, | ||
| bool | init, | ||
| bool | use_color, | ||
| int | color_index | ||
| ) | 
Definition at line 917 of file urdf_model_marker.cpp.
| void UrdfModelMarker::addGraspPointControl | ( | visualization_msgs::InteractiveMarker & | int_marker, | 
| std::string | link_frame_name_ | ||
| ) | 
Definition at line 91 of file urdf_model_marker.cpp.
| void UrdfModelMarker::addInvisibleMeshMarkerControl | ( | visualization_msgs::InteractiveMarker & | int_marker, | 
| LinkConstSharedPtr | link, | ||
| const std_msgs::ColorRGBA & | color | ||
| ) | 
Definition at line 57 of file urdf_model_marker.cpp.
| void UrdfModelMarker::addMoveMarkerControl | ( | visualization_msgs::InteractiveMarker & | int_marker, | 
| LinkConstSharedPtr | link, | ||
| bool | root | ||
| ) | 
Definition at line 19 of file urdf_model_marker.cpp.
| void UrdfModelMarker::callPublishTf | ( | ) | 
Definition at line 132 of file urdf_model_marker.cpp.
| void UrdfModelMarker::callSetDynamicTf | ( | string | parent_frame_id, | 
| string | frame_id, | ||
| geometry_msgs::Transform | transform | ||
| ) | 
Definition at line 116 of file urdf_model_marker.cpp.
| void UrdfModelMarker::getJointState | ( | ) | 
Definition at line 640 of file urdf_model_marker.cpp.
| void UrdfModelMarker::getJointState | ( | LinkConstSharedPtr | link | ) | 
Definition at line 647 of file urdf_model_marker.cpp.
| geometry_msgs::PoseStamped UrdfModelMarker::getOriginPoseStamped | ( | ) | 
Definition at line 886 of file urdf_model_marker.cpp.
Definition at line 877 of file urdf_model_marker.cpp.
| void UrdfModelMarker::graspPoint_feedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback, | 
| string | link_name | ||
| ) | 
Definition at line 530 of file urdf_model_marker.cpp.
| void UrdfModelMarker::graspPointCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 282 of file urdf_model_marker.cpp.
| void UrdfModelMarker::hideAllMarkerCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 481 of file urdf_model_marker.cpp.
| void UrdfModelMarker::hideMarkerCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 476 of file urdf_model_marker.cpp.
| void UrdfModelMarker::hideModelMarkerCB | ( | const std_msgs::EmptyConstPtr & | msg | ) | 
Definition at line 491 of file urdf_model_marker.cpp.
| void UrdfModelMarker::jointMoveCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 306 of file urdf_model_marker.cpp.
| bool UrdfModelMarker::lockJointStates | ( | std_srvs::EmptyRequest & | req, | 
| std_srvs::EmptyRequest & | res | ||
| ) | 
Definition at line 1392 of file urdf_model_marker.cpp.
| int UrdfModelMarker::main | ( | string | file | ) | 
| visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeBoxMarkerControl | ( | const geometry_msgs::PoseStamped & | stamped, | 
| Vector3 | dim, | ||
| const std_msgs::ColorRGBA & | color, | ||
| bool | use_color | ||
| ) | 
Definition at line 598 of file urdf_model_marker.cpp.
| visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeCylinderMarkerControl | ( | const geometry_msgs::PoseStamped & | stamped, | 
| double | length, | ||
| double | radius, | ||
| const std_msgs::ColorRGBA & | color, | ||
| bool | use_color | ||
| ) | 
Definition at line 580 of file urdf_model_marker.cpp.
| visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl | ( | const std::string & | mesh_resource, | 
| const geometry_msgs::PoseStamped & | stamped, | ||
| geometry_msgs::Vector3 | scale, | ||
| const std_msgs::ColorRGBA & | color, | ||
| bool | use_color | ||
| ) | 
Definition at line 544 of file urdf_model_marker.cpp.
| visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl | ( | const std::string & | mesh_resource, | 
| const geometry_msgs::PoseStamped & | stamped, | ||
| geometry_msgs::Vector3 | scale | ||
| ) | 
Definition at line 562 of file urdf_model_marker.cpp.
| visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl | ( | const std::string & | mesh_resource, | 
| const geometry_msgs::PoseStamped & | stamped, | ||
| geometry_msgs::Vector3 | scale, | ||
| const std_msgs::ColorRGBA & | color | ||
| ) | 
Definition at line 574 of file urdf_model_marker.cpp.
| visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeSphereMarkerControl | ( | const geometry_msgs::PoseStamped & | stamped, | 
| double | rad, | ||
| const std_msgs::ColorRGBA & | color, | ||
| bool | use_color | ||
| ) | 
Definition at line 617 of file urdf_model_marker.cpp.
| void UrdfModelMarker::moveCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 437 of file urdf_model_marker.cpp.
| void UrdfModelMarker::proc_feedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback, | 
| string | parent_frame_id, | ||
| string | frame_id | ||
| ) | 
Definition at line 244 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishBasePose | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 139 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishBasePose | ( | geometry_msgs::Pose | pose, | 
| std_msgs::Header | header | ||
| ) | 
Definition at line 143 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishJointState | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 188 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishJointState | ( | ) | 
Definition at line 635 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishMarkerMenu | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback, | 
| int | menu | ||
| ) | 
Definition at line 166 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishMarkerPose | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 152 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishMarkerPose | ( | geometry_msgs::Pose | pose, | 
| std_msgs::Header | header, | ||
| std::string | marker_name | ||
| ) | 
Definition at line 156 of file urdf_model_marker.cpp.
| void UrdfModelMarker::publishMoveObject | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 173 of file urdf_model_marker.cpp.
| void UrdfModelMarker::registrationCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 432 of file urdf_model_marker.cpp.
| void UrdfModelMarker::republishJointState | ( | sensor_msgs::JointState | js | ) | 
Definition at line 192 of file urdf_model_marker.cpp.
| void UrdfModelMarker::resetBaseCB | ( | ) | 
Definition at line 325 of file urdf_model_marker.cpp.
| void UrdfModelMarker::resetBaseMarkerCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 322 of file urdf_model_marker.cpp.
| void UrdfModelMarker::resetBaseMsgCB | ( | const std_msgs::EmptyConstPtr & | msg | ) | 
Definition at line 318 of file urdf_model_marker.cpp.
| void UrdfModelMarker::resetJointStatesCB | ( | const sensor_msgs::JointStateConstPtr & | msg, | 
| bool | update_root | ||
| ) | 
Definition at line 224 of file urdf_model_marker.cpp.
| void UrdfModelMarker::resetMarkerCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 312 of file urdf_model_marker.cpp.
| void UrdfModelMarker::resetRobotBase | ( | ) | 
Definition at line 337 of file urdf_model_marker.cpp.
Definition at line 353 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setJointAngle | ( | LinkConstSharedPtr | link, | 
| double | joint_angle | ||
| ) | 
Definition at line 754 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setJointState | ( | LinkConstSharedPtr | link, | 
| const sensor_msgs::JointStateConstPtr & | js | ||
| ) | 
Definition at line 826 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setOriginalPose | ( | LinkConstSharedPtr | link | ) | 
Definition at line 902 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setPoseCB | ( | ) | 
Definition at line 465 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setPoseCB | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Definition at line 472 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setRootPose | ( | geometry_msgs::PoseStamped | ps | ) | 
Definition at line 200 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setRootPoseCB | ( | const geometry_msgs::PoseStampedConstPtr & | msg | ) | 
Definition at line 197 of file urdf_model_marker.cpp.
| void UrdfModelMarker::setUrdfCB | ( | const std_msgs::StringConstPtr & | msg | ) | 
Definition at line 512 of file urdf_model_marker.cpp.
| void UrdfModelMarker::showModelMarkerCB | ( | const std_msgs::EmptyConstPtr & | msg | ) | 
Definition at line 501 of file urdf_model_marker.cpp.
| bool UrdfModelMarker::unlockJointStates | ( | std_srvs::EmptyRequest & | req, | 
| std_srvs::EmptyRequest & | res | ||
| ) | 
Definition at line 1400 of file urdf_model_marker.cpp.
| void UrdfModelMarker::updateDiagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | 
Definition at line 1409 of file urdf_model_marker.cpp.
| std::string UrdfModelMarker::base_frame  [protected] | 
Definition at line 179 of file urdf_model_marker.h.
| std::shared_ptr<diagnostic_updater::Updater> UrdfModelMarker::diagnostic_updater_  [protected] | 
Definition at line 140 of file urdf_model_marker.h.
| jsk_topic_tools::TimeAccumulator UrdfModelMarker::dynamic_tf_check_time_acc_  [protected] | 
Definition at line 142 of file urdf_model_marker.h.
Definition at line 175 of file urdf_model_marker.h.
Definition at line 176 of file urdf_model_marker.h.
| vector<string> UrdfModelMarker::fixed_link_  [protected] | 
Definition at line 198 of file urdf_model_marker.h.
Definition at line 192 of file urdf_model_marker.h.
| std::string UrdfModelMarker::frame_id_  [protected] | 
Definition at line 187 of file urdf_model_marker.h.
| ros::Subscriber UrdfModelMarker::hide_marker_  [protected] | 
Definition at line 158 of file urdf_model_marker.h.
| int UrdfModelMarker::index_  [protected] | 
Definition at line 203 of file urdf_model_marker.h.
| ros::Time UrdfModelMarker::init_stamp_  [protected] | 
Definition at line 204 of file urdf_model_marker.h.
| map<string, double> UrdfModelMarker::initial_pose_map_  [protected] | 
Definition at line 202 of file urdf_model_marker.h.
| bool UrdfModelMarker::is_joint_states_locked_  [protected] | 
Definition at line 169 of file urdf_model_marker.h.
| sensor_msgs::JointState UrdfModelMarker::joint_state_  [protected] | 
Definition at line 207 of file urdf_model_marker.h.
| sensor_msgs::JointState UrdfModelMarker::joint_state_origin_  [protected] | 
Definition at line 208 of file urdf_model_marker.h.
| boost::mutex UrdfModelMarker::joint_states_mutex_  [protected] | 
Definition at line 168 of file urdf_model_marker.h.
| map<string, linkProperty> UrdfModelMarker::linkMarkerMap  [protected] | 
Definition at line 246 of file urdf_model_marker.h.
| string UrdfModelMarker::mode_  [protected] | 
Definition at line 197 of file urdf_model_marker.h.
| ModelInterfaceSharedPtr UrdfModelMarker::model  [protected] | 
Definition at line 184 of file urdf_model_marker.h.
| std::string UrdfModelMarker::model_description_  [protected] | 
Definition at line 186 of file urdf_model_marker.h.
| std::string UrdfModelMarker::model_file_  [protected] | 
Definition at line 188 of file urdf_model_marker.h.
Definition at line 170 of file urdf_model_marker.h.
| std::string UrdfModelMarker::model_name_  [protected] | 
Definition at line 185 of file urdf_model_marker.h.
| std::string UrdfModelMarker::move_base_frame  [protected] | 
Definition at line 180 of file urdf_model_marker.h.
| ros::NodeHandle UrdfModelMarker::nh_  [protected] | 
Definition at line 135 of file urdf_model_marker.h.
| ros::NodeHandle UrdfModelMarker::pnh_  [protected] | 
Definition at line 136 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_  [protected] | 
Definition at line 145 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_base_pose_  [protected] | 
Definition at line 150 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_joint_state_  [protected] | 
Definition at line 149 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_move_  [protected] | 
Definition at line 146 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_move_model_  [protected] | 
Definition at line 148 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_move_object_  [protected] | 
Definition at line 147 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_selected_  [protected] | 
Definition at line 151 of file urdf_model_marker.h.
| ros::Publisher UrdfModelMarker::pub_selected_index_  [protected] | 
Definition at line 152 of file urdf_model_marker.h.
| bool UrdfModelMarker::registration_  [protected] | 
Definition at line 195 of file urdf_model_marker.h.
| jsk_topic_tools::TimeAccumulator UrdfModelMarker::reset_joint_states_check_time_acc_  [protected] | 
Definition at line 141 of file urdf_model_marker.h.
| bool UrdfModelMarker::robot_mode_  [protected] | 
Definition at line 194 of file urdf_model_marker.h.
| geometry_msgs::Pose UrdfModelMarker::root_offset_  [protected] | 
Definition at line 191 of file urdf_model_marker.h.
| geometry_msgs::Pose UrdfModelMarker::root_pose_  [protected] | 
Definition at line 189 of file urdf_model_marker.h.
Definition at line 190 of file urdf_model_marker.h.
| double UrdfModelMarker::scale_factor_  [protected] | 
Definition at line 193 of file urdf_model_marker.h.
Definition at line 166 of file urdf_model_marker.h.
| ros::ServiceServer UrdfModelMarker::serv_markers_del_  [protected] | 
Definition at line 165 of file urdf_model_marker.h.
| ros::ServiceServer UrdfModelMarker::serv_markers_set_  [protected] | 
Definition at line 164 of file urdf_model_marker.h.
| ros::ServiceServer UrdfModelMarker::serv_reset_  [protected] | 
Definition at line 162 of file urdf_model_marker.h.
| ros::ServiceServer UrdfModelMarker::serv_set_  [protected] | 
Definition at line 163 of file urdf_model_marker.h.
Definition at line 167 of file urdf_model_marker.h.
| std::shared_ptr<interactive_markers::InteractiveMarkerServer> UrdfModelMarker::server_  [protected] | 
Definition at line 137 of file urdf_model_marker.h.
| std::string UrdfModelMarker::server_name  [protected] | 
Definition at line 178 of file urdf_model_marker.h.
| ros::Subscriber UrdfModelMarker::show_marker_  [protected] | 
Definition at line 159 of file urdf_model_marker.h.
| ros::Subscriber UrdfModelMarker::sub_reset_joints_  [protected] | 
Definition at line 155 of file urdf_model_marker.h.
Definition at line 156 of file urdf_model_marker.h.
| ros::Subscriber UrdfModelMarker::sub_set_root_pose_  [protected] | 
Definition at line 157 of file urdf_model_marker.h.
| ros::Subscriber UrdfModelMarker::sub_set_urdf_  [protected] | 
Definition at line 160 of file urdf_model_marker.h.
| std::string UrdfModelMarker::target_frame  [protected] | 
Definition at line 181 of file urdf_model_marker.h.
| std::string UrdfModelMarker::tf_prefix_  [protected] | 
Definition at line 201 of file urdf_model_marker.h.
| tf::TransformBroadcaster UrdfModelMarker::tfb_  [protected] | 
Definition at line 173 of file urdf_model_marker.h.
| tf::TransformListener UrdfModelMarker::tfl_  [protected] | 
Definition at line 172 of file urdf_model_marker.h.
| bool UrdfModelMarker::use_dynamic_tf_  [protected] | 
Definition at line 196 of file urdf_model_marker.h.
| bool UrdfModelMarker::use_robot_description_  [protected] | 
Definition at line 199 of file urdf_model_marker.h.
| bool UrdfModelMarker::use_visible_color_  [protected] | 
Definition at line 200 of file urdf_model_marker.h.