1 #ifndef _URDF_MODEL_MARKER_H_ 
    2 #define _URDF_MODEL_MARKER_H_ 
   14 #include <jsk_interactive_marker/SetPose.h> 
   15 #include <jsk_interactive_marker/MarkerSetPose.h> 
   18 #include <jsk_interactive_marker/MarkerMenu.h> 
   19 #include <jsk_interactive_marker/MarkerPose.h> 
   20 #include <jsk_interactive_marker/MoveObject.h> 
   21 #include <jsk_interactive_marker/MoveModel.h> 
   23 #include <std_msgs/Int8.h> 
   24 #include <std_msgs/String.h> 
   25 #include <std_srvs/Empty.h> 
   26 #include <sensor_msgs/JointState.h> 
   28 #include "urdf_parser/urdf_parser.h" 
   35 #include <jsk_recognition_msgs/Int32Stamped.h> 
   37 #include <jsk_topic_tools/time_accumulator.h> 
   39 #if ROS_VERSION_MINIMUM(1,12,0) // kinetic 
   40 #include <urdf_model/types.h> 
   41 #include <urdf_world/types.h> 
   58   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);
 
   61   void addMoveMarkerControl(visualization_msgs::InteractiveMarker &int_marker, 
LinkConstSharedPtr link, 
bool root);
 
   62   void addInvisibleMeshMarkerControl(visualization_msgs::InteractiveMarker &int_marker, 
LinkConstSharedPtr link, 
const std_msgs::ColorRGBA &color);
 
   63   void addGraspPointControl(visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_);
 
   65   void publishBasePose( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   66   void publishBasePose( geometry_msgs::Pose 
pose, std_msgs::Header 
header);
 
   67   void publishMarkerPose ( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
 
   68   void publishMarkerPose ( geometry_msgs::Pose 
pose, std_msgs::Header 
header, std::string marker_name);
 
   69   void publishMarkerMenu( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, 
int menu );
 
   70   void publishMoveObject( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   71   void publishJointState( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   72   void republishJointState( sensor_msgs::JointState js);
 
   74   void proc_feedback( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, 
string parent_frame_id, 
string frame_id);
 
   76   void graspPoint_feedback( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, 
string link_name);
 
   77   void moveCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   79   void setPoseCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   80   void hideMarkerCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   81   void hideAllMarkerCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   83   void hideModelMarkerCB( 
const std_msgs::EmptyConstPtr &
msg);
 
   84   void showModelMarkerCB( 
const std_msgs::EmptyConstPtr &
msg);
 
   85   void setUrdfCB( 
const std_msgs::StringConstPtr &
msg);
 
   87   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);
 
   89   visualization_msgs::InteractiveMarkerControl 
makeMeshMarkerControl(
const std::string &
mesh_resource, 
const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 
scale, 
const std_msgs::ColorRGBA &color);
 
   93   visualization_msgs::InteractiveMarkerControl 
makeCylinderMarkerControl(
const geometry_msgs::PoseStamped &stamped, 
double length, 
double radius, 
const std_msgs::ColorRGBA &color, 
bool use_color);
 
   94   visualization_msgs::InteractiveMarkerControl 
makeBoxMarkerControl(
const geometry_msgs::PoseStamped &stamped, Vector3 dim, 
const std_msgs::ColorRGBA &color, 
bool use_color);
 
   95   visualization_msgs::InteractiveMarkerControl 
makeSphereMarkerControl(
const geometry_msgs::PoseStamped &stamped, 
double rad, 
const std_msgs::ColorRGBA &color, 
bool use_color);
 
   97   void publishJointState();
 
  101   void setJointState(
LinkConstSharedPtr link, 
const sensor_msgs::JointStateConstPtr &js);
 
  103   geometry_msgs::Pose getRootPose(geometry_msgs::Pose 
pose);
 
  104   geometry_msgs::PoseStamped getOriginPoseStamped();
 
  109   void callSetDynamicTf(
string parent_frame_id, 
string frame_id, geometry_msgs::Transform transform);
 
  110   void callPublishTf();
 
  114   void graspPointCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
  115   void jointMoveCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
  116   void resetMarkerCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
  117   void resetBaseMarkerCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
  118   void resetBaseMsgCB( 
const std_msgs::EmptyConstPtr &
msg);
 
  121   void resetRobotBase();
 
  122   void resetRootForVisualization();
 
  123   void registrationCB( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
  125   void setRootPoseCB( 
const geometry_msgs::PoseStampedConstPtr &
msg );
 
  126   void setRootPose( geometry_msgs::PoseStamped ps);
 
  127   void resetJointStatesCB( 
const sensor_msgs::JointStateConstPtr &
msg, 
bool update_root);
 
  129   bool lockJointStates(std_srvs::EmptyRequest& req,
 
  130                        std_srvs::EmptyRequest& res);
 
  131   bool unlockJointStates(std_srvs::EmptyRequest& req,
 
  132                          std_srvs::EmptyRequest& res);
 
  137   std::shared_ptr<interactive_markers::InteractiveMarkerServer> 
server_;
 
  212       displayMoveMarker = 
false;
 
  213       displayGraspPoint = 
false;
 
  214       pose.orientation.x = 0;
 
  215       pose.orientation.y = 0;
 
  216       pose.orientation.z = 0;
 
  217       pose.orientation.w = 1;
 
  227       displayMoveMarker = 
false;
 
  228       displayModelMarker = 
true;