Classes | Public Member Functions | Protected Attributes
UrdfModelMarker Class Reference

#include <urdf_model_marker.h>

List of all members.

Classes

struct  graspPoint
struct  linkProperty

Public Member Functions

void addChildLinkNames (boost::shared_ptr< const Link > link, bool root, bool init)
void addChildLinkNames (boost::shared_ptr< const Link > 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, boost::shared_ptr< const Link > link, const std_msgs::ColorRGBA &color)
void addMoveMarkerControl (visualization_msgs::InteractiveMarker &int_marker, boost::shared_ptr< const Link > link, bool root)
void callPublishTf ()
void callSetDynamicTf (string parent_frame_id, string frame_id, geometry_msgs::Transform transform)
void getJointState ()
void getJointState (boost::shared_ptr< const Link > 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 (boost::shared_ptr< const Link > link, double joint_angle)
void setJointState (boost::shared_ptr< const Link > link, const sensor_msgs::JointStateConstPtr &js)
void setOriginalPose (boost::shared_ptr< const Link > 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, boost::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, boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server)
 UrdfModelMarker ()

Protected Attributes

std::string base_frame
boost::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< stringfixed_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, linkPropertylinkMarkerMap
string mode_
boost::shared_ptr< ModelInterface > 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_
boost::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_

Detailed Description

Definition at line 43 of file urdf_model_marker.h.


Constructor & Destructor Documentation

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,
boost::shared_ptr< interactive_markers::InteractiveMarkerServer server 
)

Definition at line 1144 of file urdf_model_marker.cpp.

Definition at line 1141 of file urdf_model_marker.cpp.


Member Function Documentation

void UrdfModelMarker::addChildLinkNames ( boost::shared_ptr< const Link >  link,
bool  root,
bool  init 
)

Definition at line 906 of file urdf_model_marker.cpp.

void UrdfModelMarker::addChildLinkNames ( boost::shared_ptr< const Link >  link,
bool  root,
bool  init,
bool  use_color,
int  color_index 
)

Definition at line 911 of file urdf_model_marker.cpp.

void UrdfModelMarker::addGraspPointControl ( visualization_msgs::InteractiveMarker &  int_marker,
std::string  link_frame_name_ 
)

Definition at line 89 of file urdf_model_marker.cpp.

void UrdfModelMarker::addInvisibleMeshMarkerControl ( visualization_msgs::InteractiveMarker &  int_marker,
boost::shared_ptr< const Link >  link,
const std_msgs::ColorRGBA &  color 
)

Definition at line 55 of file urdf_model_marker.cpp.

void UrdfModelMarker::addMoveMarkerControl ( visualization_msgs::InteractiveMarker &  int_marker,
boost::shared_ptr< const Link >  link,
bool  root 
)

Definition at line 18 of file urdf_model_marker.cpp.

Definition at line 130 of file urdf_model_marker.cpp.

void UrdfModelMarker::callSetDynamicTf ( string  parent_frame_id,
string  frame_id,
geometry_msgs::Transform  transform 
)

Definition at line 114 of file urdf_model_marker.cpp.

Definition at line 636 of file urdf_model_marker.cpp.

void UrdfModelMarker::getJointState ( boost::shared_ptr< const Link >  link)

Definition at line 643 of file urdf_model_marker.cpp.

geometry_msgs::PoseStamped UrdfModelMarker::getOriginPoseStamped ( )

Definition at line 880 of file urdf_model_marker.cpp.

Definition at line 871 of file urdf_model_marker.cpp.

void UrdfModelMarker::graspPoint_feedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
string  link_name 
)

Definition at line 526 of file urdf_model_marker.cpp.

void UrdfModelMarker::graspPointCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 279 of file urdf_model_marker.cpp.

void UrdfModelMarker::hideAllMarkerCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 477 of file urdf_model_marker.cpp.

void UrdfModelMarker::hideMarkerCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 472 of file urdf_model_marker.cpp.

void UrdfModelMarker::hideModelMarkerCB ( const std_msgs::EmptyConstPtr &  msg)

Definition at line 487 of file urdf_model_marker.cpp.

void UrdfModelMarker::jointMoveCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 303 of file urdf_model_marker.cpp.

bool UrdfModelMarker::lockJointStates ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyRequest &  res 
)

Definition at line 1343 of file urdf_model_marker.cpp.

visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeBoxMarkerControl ( const geometry_msgs::PoseStamped &  stamped,
Vector3  dim,
const std_msgs::ColorRGBA &  color,
bool  use_color 
)

Definition at line 594 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 576 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 540 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 558 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 570 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 613 of file urdf_model_marker.cpp.

void UrdfModelMarker::moveCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 433 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 242 of file urdf_model_marker.cpp.

void UrdfModelMarker::publishBasePose ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 137 of file urdf_model_marker.cpp.

Definition at line 141 of file urdf_model_marker.cpp.

void UrdfModelMarker::publishJointState ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 186 of file urdf_model_marker.cpp.

Definition at line 631 of file urdf_model_marker.cpp.

void UrdfModelMarker::publishMarkerMenu ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback,
int  menu 
)

Definition at line 164 of file urdf_model_marker.cpp.

void UrdfModelMarker::publishMarkerPose ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 150 of file urdf_model_marker.cpp.

Definition at line 154 of file urdf_model_marker.cpp.

void UrdfModelMarker::publishMoveObject ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 171 of file urdf_model_marker.cpp.

void UrdfModelMarker::registrationCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 428 of file urdf_model_marker.cpp.

void UrdfModelMarker::republishJointState ( sensor_msgs::JointState  js)

Definition at line 190 of file urdf_model_marker.cpp.

Definition at line 322 of file urdf_model_marker.cpp.

void UrdfModelMarker::resetBaseMarkerCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 319 of file urdf_model_marker.cpp.

void UrdfModelMarker::resetBaseMsgCB ( const std_msgs::EmptyConstPtr &  msg)

Definition at line 315 of file urdf_model_marker.cpp.

void UrdfModelMarker::resetJointStatesCB ( const sensor_msgs::JointStateConstPtr &  msg,
bool  update_root 
)

Definition at line 222 of file urdf_model_marker.cpp.

void UrdfModelMarker::resetMarkerCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 309 of file urdf_model_marker.cpp.

Definition at line 334 of file urdf_model_marker.cpp.

Definition at line 350 of file urdf_model_marker.cpp.

void UrdfModelMarker::setJointAngle ( boost::shared_ptr< const Link >  link,
double  joint_angle 
)

Definition at line 749 of file urdf_model_marker.cpp.

void UrdfModelMarker::setJointState ( boost::shared_ptr< const Link >  link,
const sensor_msgs::JointStateConstPtr &  js 
)

Definition at line 820 of file urdf_model_marker.cpp.

void UrdfModelMarker::setOriginalPose ( boost::shared_ptr< const Link >  link)

Definition at line 896 of file urdf_model_marker.cpp.

Definition at line 461 of file urdf_model_marker.cpp.

void UrdfModelMarker::setPoseCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Definition at line 468 of file urdf_model_marker.cpp.

void UrdfModelMarker::setRootPose ( geometry_msgs::PoseStamped  ps)

Definition at line 198 of file urdf_model_marker.cpp.

void UrdfModelMarker::setRootPoseCB ( const geometry_msgs::PoseStampedConstPtr &  msg)

Definition at line 195 of file urdf_model_marker.cpp.

void UrdfModelMarker::setUrdfCB ( const std_msgs::StringConstPtr &  msg)

Definition at line 508 of file urdf_model_marker.cpp.

void UrdfModelMarker::showModelMarkerCB ( const std_msgs::EmptyConstPtr &  msg)

Definition at line 497 of file urdf_model_marker.cpp.

bool UrdfModelMarker::unlockJointStates ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyRequest &  res 
)

Definition at line 1351 of file urdf_model_marker.cpp.

Definition at line 1360 of file urdf_model_marker.cpp.


Member Data Documentation

Definition at line 168 of file urdf_model_marker.h.

Definition at line 129 of file urdf_model_marker.h.

Definition at line 131 of file urdf_model_marker.h.

Definition at line 164 of file urdf_model_marker.h.

Definition at line 165 of file urdf_model_marker.h.

Definition at line 187 of file urdf_model_marker.h.

Definition at line 181 of file urdf_model_marker.h.

Definition at line 176 of file urdf_model_marker.h.

Definition at line 147 of file urdf_model_marker.h.

int UrdfModelMarker::index_ [protected]

Definition at line 192 of file urdf_model_marker.h.

Definition at line 193 of file urdf_model_marker.h.

map<string, double> UrdfModelMarker::initial_pose_map_ [protected]

Definition at line 191 of file urdf_model_marker.h.

Definition at line 158 of file urdf_model_marker.h.

sensor_msgs::JointState UrdfModelMarker::joint_state_ [protected]

Definition at line 196 of file urdf_model_marker.h.

sensor_msgs::JointState UrdfModelMarker::joint_state_origin_ [protected]

Definition at line 197 of file urdf_model_marker.h.

Definition at line 157 of file urdf_model_marker.h.

Definition at line 235 of file urdf_model_marker.h.

Definition at line 186 of file urdf_model_marker.h.

boost::shared_ptr<ModelInterface> UrdfModelMarker::model [protected]

Definition at line 173 of file urdf_model_marker.h.

Definition at line 175 of file urdf_model_marker.h.

Definition at line 177 of file urdf_model_marker.h.

Definition at line 159 of file urdf_model_marker.h.

Definition at line 174 of file urdf_model_marker.h.

Definition at line 169 of file urdf_model_marker.h.

Definition at line 124 of file urdf_model_marker.h.

Definition at line 125 of file urdf_model_marker.h.

Definition at line 134 of file urdf_model_marker.h.

Definition at line 139 of file urdf_model_marker.h.

Definition at line 138 of file urdf_model_marker.h.

Definition at line 135 of file urdf_model_marker.h.

Definition at line 137 of file urdf_model_marker.h.

Definition at line 136 of file urdf_model_marker.h.

Definition at line 140 of file urdf_model_marker.h.

Definition at line 141 of file urdf_model_marker.h.

Definition at line 184 of file urdf_model_marker.h.

Definition at line 130 of file urdf_model_marker.h.

bool UrdfModelMarker::robot_mode_ [protected]

Definition at line 183 of file urdf_model_marker.h.

Definition at line 180 of file urdf_model_marker.h.

Definition at line 178 of file urdf_model_marker.h.

Definition at line 179 of file urdf_model_marker.h.

double UrdfModelMarker::scale_factor_ [protected]

Definition at line 182 of file urdf_model_marker.h.

Definition at line 155 of file urdf_model_marker.h.

Definition at line 154 of file urdf_model_marker.h.

Definition at line 153 of file urdf_model_marker.h.

Definition at line 151 of file urdf_model_marker.h.

Definition at line 152 of file urdf_model_marker.h.

Definition at line 156 of file urdf_model_marker.h.

Definition at line 126 of file urdf_model_marker.h.

Definition at line 167 of file urdf_model_marker.h.

Definition at line 148 of file urdf_model_marker.h.

Definition at line 144 of file urdf_model_marker.h.

Definition at line 145 of file urdf_model_marker.h.

Definition at line 146 of file urdf_model_marker.h.

Definition at line 149 of file urdf_model_marker.h.

Definition at line 170 of file urdf_model_marker.h.

Definition at line 190 of file urdf_model_marker.h.

Definition at line 162 of file urdf_model_marker.h.

Definition at line 161 of file urdf_model_marker.h.

Definition at line 185 of file urdf_model_marker.h.

Definition at line 188 of file urdf_model_marker.h.

Definition at line 189 of file urdf_model_marker.h.


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


jsk_interactive_marker
Author(s): furuta
autogenerated on Sun Sep 13 2015 22:29:27