00001 #ifndef _URDF_MODEL_MARKER_H_
00002 #define _URDF_MODEL_MARKER_H_
00003
00004
00005 #include <ros/ros.h>
00006
00007 #include <tf/tf.h>
00008 #include <tf/transform_listener.h>
00009 #include <tf/transform_broadcaster.h>
00010
00011 #include <interactive_markers/interactive_marker_server.h>
00012
00013 #include <interactive_markers/menu_handler.h>
00014 #include <jsk_interactive_marker/SetPose.h>
00015 #include <jsk_interactive_marker/MarkerSetPose.h>
00016
00017 #include <math.h>
00018 #include <jsk_interactive_marker/MarkerMenu.h>
00019 #include <jsk_interactive_marker/MarkerPose.h>
00020 #include <jsk_interactive_marker/MoveObject.h>
00021 #include <jsk_interactive_marker/MoveModel.h>
00022
00023 #include <std_msgs/Int8.h>
00024 #include <std_msgs/String.h>
00025 #include <std_srvs/Empty.h>
00026 #include <sensor_msgs/JointState.h>
00027
00028 #include "urdf_parser/urdf_parser.h"
00029 #include <iostream>
00030 #include <fstream>
00031
00032 #include <diagnostic_updater/diagnostic_updater.h>
00033 #include <diagnostic_updater/publisher.h>
00034
00035 #include <jsk_recognition_msgs/Int32Stamped.h>
00036
00037 #include <jsk_topic_tools/time_accumulator.h>
00038
00039 using namespace urdf;
00040 using namespace std;
00041
00042
00043 class UrdfModelMarker {
00044 public:
00045
00046 UrdfModelMarker(string file, boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server);
00047 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);
00048 UrdfModelMarker();
00049
00050 void addMoveMarkerControl(visualization_msgs::InteractiveMarker &int_marker, boost::shared_ptr<const Link> link, bool root);
00051 void addInvisibleMeshMarkerControl(visualization_msgs::InteractiveMarker &int_marker, boost::shared_ptr<const Link> link, const std_msgs::ColorRGBA &color);
00052 void addGraspPointControl(visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_);
00053
00054 void publishBasePose( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00055 void publishBasePose( geometry_msgs::Pose pose, std_msgs::Header header);
00056 void publishMarkerPose ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00057 void publishMarkerPose ( geometry_msgs::Pose pose, std_msgs::Header header, std::string marker_name);
00058 void publishMarkerMenu( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu );
00059 void publishMoveObject( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00060 void publishJointState( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00061 void republishJointState( sensor_msgs::JointState js);
00062
00063 void proc_feedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string parent_frame_id, string frame_id);
00064
00065 void graspPoint_feedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string link_name);
00066 void moveCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00067 void setPoseCB();
00068 void setPoseCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00069 void hideMarkerCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00070 void hideAllMarkerCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00071
00072 void hideModelMarkerCB( const std_msgs::EmptyConstPtr &msg);
00073 void showModelMarkerCB( const std_msgs::EmptyConstPtr &msg);
00074 void setUrdfCB( const std_msgs::StringConstPtr &msg);
00075
00076 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);
00077 visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale);
00078 visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color);
00079
00080
00081
00082 visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color);
00083 visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color);
00084 visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color);
00085
00086 void publishJointState();
00087 void getJointState();
00088 void getJointState(boost::shared_ptr<const Link> link);
00089
00090 void setJointState(boost::shared_ptr<const Link> link, const sensor_msgs::JointStateConstPtr &js);
00091 void setJointAngle(boost::shared_ptr<const Link> link, double joint_angle);
00092 geometry_msgs::Pose getRootPose(geometry_msgs::Pose pose);
00093 geometry_msgs::PoseStamped getOriginPoseStamped();
00094 void setOriginalPose(boost::shared_ptr<const Link> link);
00095 void addChildLinkNames(boost::shared_ptr<const Link> link, bool root, bool init);
00096 void addChildLinkNames(boost::shared_ptr<const Link> link, bool root, bool init, bool use_color, int color_index);
00097
00098 void callSetDynamicTf(string parent_frame_id, string frame_id, geometry_msgs::Transform transform);
00099 void callPublishTf();
00100
00101 int main(string file);
00102
00103 void graspPointCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00104 void jointMoveCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00105 void resetMarkerCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00106 void resetBaseMarkerCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00107 void resetBaseMsgCB( const std_msgs::EmptyConstPtr &msg);
00108 void resetBaseCB();
00109
00110 void resetRobotBase();
00111 void resetRootForVisualization();
00112 void registrationCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00113
00114 void setRootPoseCB( const geometry_msgs::PoseStampedConstPtr &msg );
00115 void setRootPose( geometry_msgs::PoseStamped ps);
00116 void resetJointStatesCB( const sensor_msgs::JointStateConstPtr &msg, bool update_root);
00117 void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat);
00118 bool lockJointStates(std_srvs::EmptyRequest& req,
00119 std_srvs::EmptyRequest& res);
00120 bool unlockJointStates(std_srvs::EmptyRequest& req,
00121 std_srvs::EmptyRequest& res);
00122
00123 protected:
00124 ros::NodeHandle nh_;
00125 ros::NodeHandle pnh_;
00126 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
00127
00128
00129 boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00130 jsk_topic_tools::TimeAccumulator reset_joint_states_check_time_acc_;
00131 jsk_topic_tools::TimeAccumulator dynamic_tf_check_time_acc_;
00132
00133
00134 ros::Publisher pub_;
00135 ros::Publisher pub_move_;
00136 ros::Publisher pub_move_object_;
00137 ros::Publisher pub_move_model_;
00138 ros::Publisher pub_joint_state_;
00139 ros::Publisher pub_base_pose_;
00140 ros::Publisher pub_selected_;
00141 ros::Publisher pub_selected_index_;
00142
00143
00144 ros::Subscriber sub_reset_joints_;
00145 ros::Subscriber sub_reset_joints_and_root_;
00146 ros::Subscriber sub_set_root_pose_;
00147 ros::Subscriber hide_marker_;
00148 ros::Subscriber show_marker_;
00149 ros::Subscriber sub_set_urdf_;
00150
00151 ros::ServiceServer serv_reset_;
00152 ros::ServiceServer serv_set_;
00153 ros::ServiceServer serv_markers_set_;
00154 ros::ServiceServer serv_markers_del_;
00155 ros::ServiceServer serv_lock_joint_states_;
00156 ros::ServiceServer serv_unlock_joint_states_;
00157 boost::mutex joint_states_mutex_;
00158 bool is_joint_states_locked_;
00159 interactive_markers::MenuHandler model_menu_;
00160
00161 tf::TransformListener tfl_;
00162 tf::TransformBroadcaster tfb_;
00163
00164 ros::ServiceClient dynamic_tf_publisher_client;
00165 ros::ServiceClient dynamic_tf_publisher_publish_tf_client;
00166
00167 std::string server_name;
00168 std::string base_frame;
00169 std::string move_base_frame;
00170 std::string target_frame;
00171
00172
00173 boost::shared_ptr<ModelInterface> model;
00174 std::string model_name_;
00175 std::string model_description_;
00176 std::string frame_id_;
00177 std::string model_file_;
00178 geometry_msgs::Pose root_pose_;
00179 geometry_msgs::Pose root_pose_origin_;
00180 geometry_msgs::Pose root_offset_;
00181 geometry_msgs::Pose fixed_link_offset_;
00182 double scale_factor_;
00183 bool robot_mode_;
00184 bool registration_;
00185 bool use_dynamic_tf_;
00186 string mode_;
00187 vector<string> fixed_link_;
00188 bool use_robot_description_;
00189 bool use_visible_color_;
00190 std::string tf_prefix_;
00191 map<string, double> initial_pose_map_;
00192 int index_;
00193 ros::Time init_stamp_;
00194
00195
00196 sensor_msgs::JointState joint_state_;
00197 sensor_msgs::JointState joint_state_origin_;
00198
00199 struct graspPoint{
00200 graspPoint(){
00201 displayMoveMarker = false;
00202 displayGraspPoint = false;
00203 pose.orientation.x = 0;
00204 pose.orientation.y = 0;
00205 pose.orientation.z = 0;
00206 pose.orientation.w = 1;
00207 }
00208 bool displayGraspPoint;
00209 bool displayMoveMarker;
00210 geometry_msgs::Pose pose;
00211 };
00212
00213
00214 struct linkProperty{
00215 linkProperty(){
00216 displayMoveMarker = false;
00217 displayModelMarker = true;
00218 mesh_file = "";
00219 }
00220 bool displayMoveMarker;
00221 bool displayModelMarker;
00222 graspPoint gp;
00223 string frame_id;
00224 string movable_link;
00225
00226 geometry_msgs::Pose pose;
00227 geometry_msgs::Pose origin;
00228 geometry_msgs::Pose initial_pose;
00229 urdf::Vector3 joint_axis;
00230 double joint_angle;
00231 int rotation_count;
00232 string mesh_file;
00233 };
00234
00235 map<string, linkProperty> linkMarkerMap;
00236 };
00237
00238 #endif