00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/ros.h>
00037 #include <interactive_markers/interactive_marker_server.h>
00038 #include <interactive_markers/tools.h>
00039 #include <interactive_markers/menu_handler.h>
00040 #include <tf/transform_broadcaster.h>
00041 #include <geometry_msgs/PoseStamped.h>
00042 #include <tf_conversions/tf_eigen.h>
00043 #include <jsk_topic_tools/rosparam_utils.h>
00044
00045 class Marker6DOF {
00046 public:
00047 Marker6DOF(): show_6dof_circle_(true) {
00048 ros::NodeHandle nh, pnh("~");
00049 pnh.param("frame_id", frame_id_, std::string("/map"));
00050 pnh.param("publish_tf", publish_tf_, false);
00051 pnh.param("tf_frame", tf_frame_, std::string("object"));
00052 double tf_duration;
00053 pnh.param("tf_duration", tf_duration, 0.1);
00054 pnh.param("object_type", object_type_, std::string("sphere"));
00055 pnh.param("object_x", object_x_, 1.0);
00056 pnh.param("object_y", object_y_, 1.0);
00057 pnh.param("object_z", object_z_, 1.0);
00058 pnh.param("object_r", object_r_, 1.0);
00059 pnh.param("object_g", object_g_, 1.0);
00060 pnh.param("object_b", object_b_, 1.0);
00061 pnh.param("object_a", object_a_, 1.0);
00062 double initial_x, initial_y, initial_z;
00063 pnh.param("initial_x", initial_x, 0.0);
00064 pnh.param("initial_y", initial_y, 0.0);
00065 pnh.param("initial_z", initial_z, 0.0);
00066 latest_pose_.pose.position.x = initial_x;
00067 latest_pose_.pose.position.y = initial_y;
00068 latest_pose_.pose.position.z = initial_z;
00069 std::vector<double> initial_orientation;
00070 if (jsk_topic_tools::readVectorParameter(pnh, "initial_orientation", initial_orientation)) {
00071 latest_pose_.pose.orientation.x = initial_orientation[0];
00072 latest_pose_.pose.orientation.y = initial_orientation[1];
00073 latest_pose_.pose.orientation.z = initial_orientation[2];
00074 latest_pose_.pose.orientation.w = initial_orientation[3];
00075 }
00076 else {
00077 latest_pose_.pose.orientation.w = 1.0;
00078 }
00079 pnh.param("line_width", line_width_, 0.007);
00080 if (publish_tf_) {
00081 tf_broadcaster_.reset(new tf::TransformBroadcaster);
00082 }
00083 latest_pose_.header.frame_id = frame_id_;
00084
00085 pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("pose", 1);
00086 pose_stamped_sub_ = pnh.subscribe("move_marker", 1, &Marker6DOF::moveMarkerCB, this);
00087
00088 circle_menu_entry_
00089 = menu_handler_.insert("Toggle 6DOF Circle",
00090 boost::bind(&Marker6DOF::menuFeedbackCB, this, _1));
00091 menu_handler_.setCheckState(circle_menu_entry_,
00092 interactive_markers::MenuHandler::CHECKED);
00093 server_.reset( new interactive_markers::InteractiveMarkerServer(ros::this_node::getName()));
00094 initializeInteractiveMarker();
00095 if (publish_tf_) {
00096 timer_ = nh.createTimer(ros::Duration(tf_duration), boost::bind(&Marker6DOF::timerCallback, this, _1));
00097 }
00098 }
00099
00100 protected:
00101 void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg) {
00102 boost::mutex::scoped_lock lock(mutex_);
00103 pose_pub_.publish(msg);
00104 server_->setPose("marker", msg->pose, msg->header);
00105 latest_pose_ = geometry_msgs::PoseStamped(*msg);
00106 server_->applyChanges();
00107 }
00108
00109
00110 void calculateBoundingBox( visualization_msgs::Marker& object_marker){
00111 geometry_msgs::Point top[5];
00112 top[0].x = object_x_/2;
00113 top[0].y = object_y_/2;
00114 top[1].x = -object_x_/2;
00115 top[1].y = object_y_/2;
00116 top[2].x = -object_x_/2;
00117 top[2].y = -object_y_/2;
00118 top[3].x = object_x_/2;
00119 top[3].y = -object_y_/2;
00120 top[4].x = object_x_/2;
00121 top[4].y = object_y_/2;
00122
00123 geometry_msgs::Point bottom[5];
00124 bottom[0].x = object_x_/2;
00125 bottom[0].y = object_y_/2;
00126 bottom[1].x = -object_x_/2;
00127 bottom[1].y = object_y_/2;
00128 bottom[2].x = -object_x_/2;
00129 bottom[2].y = -object_y_/2;
00130 bottom[3].x = object_x_/2;
00131 bottom[3].y = -object_y_/2;
00132 bottom[4].x = object_x_/2;
00133 bottom[4].y = object_y_/2;
00134
00135 for(int i = 0; i< 5; i++){
00136 top[i].z = object_z_/2;
00137 bottom[i].z = -object_z_/2;
00138 }
00139
00140 for(int i = 0; i< 4; i++){
00141 object_marker.points.push_back(top[i]);
00142 object_marker.points.push_back(top[i+1]);
00143 object_marker.points.push_back(bottom[i]);
00144 object_marker.points.push_back(bottom[i+1]);
00145 object_marker.points.push_back(top[i]);
00146 object_marker.points.push_back(bottom[i]);
00147 }
00148 }
00149
00150 void initializeInteractiveMarker() {
00151 visualization_msgs::InteractiveMarker int_marker;
00152 int_marker.header.frame_id = latest_pose_.header.frame_id;
00153 int_marker.name = "marker";
00154 int_marker.pose = geometry_msgs::Pose(latest_pose_.pose);
00155
00156 visualization_msgs::Marker object_marker;
00157 if(object_type_ == std::string("cube")){
00158 object_marker.type = visualization_msgs::Marker::CUBE;
00159 object_marker.scale.x = object_x_;
00160 object_marker.scale.y = object_y_;
00161 object_marker.scale.z = object_z_;
00162 object_marker.color.r = object_r_;
00163 object_marker.color.g = object_g_;
00164 object_marker.color.b = object_b_;
00165 object_marker.color.a = object_a_;
00166 object_marker.pose.orientation.w = 1.0;
00167 }
00168 else if( object_type_ == std::string("sphere") ){
00169 object_marker.type = visualization_msgs::Marker::SPHERE;
00170 object_marker.scale.x = object_x_;
00171 object_marker.scale.y = object_y_;
00172 object_marker.scale.z = object_z_;
00173 object_marker.color.r = object_r_;
00174 object_marker.color.g = object_g_;
00175 object_marker.color.b = object_b_;
00176 object_marker.color.a = object_a_;
00177 object_marker.pose.orientation.w = 1.0;
00178 }else if(object_type_ == std::string("line")){
00179 object_marker.type = visualization_msgs::Marker::LINE_LIST;
00180 object_marker.scale.x = line_width_;
00181 object_marker.color.g = object_g_;
00182 object_marker.color.b = object_b_;
00183 object_marker.color.a = object_a_;
00184 object_marker.pose.orientation.w = 1.0;
00185 calculateBoundingBox(object_marker);
00186 }
00187
00188
00189 visualization_msgs::InteractiveMarkerControl object_marker_control;
00190 object_marker_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00191 object_marker_control.always_visible = true;
00192 object_marker_control.markers.push_back(object_marker);
00193 int_marker.controls.push_back(object_marker_control);
00194
00195 visualization_msgs::InteractiveMarkerControl control;
00196 if (show_6dof_circle_) {
00197 control.orientation.w = 1;
00198 control.orientation.x = 1;
00199 control.orientation.y = 0;
00200 control.orientation.z = 0;
00201
00202 control.name = "rotate_x";
00203 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00204 int_marker.controls.push_back(control);
00205 control.name = "move_x";
00206 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00207 int_marker.controls.push_back(control);
00208
00209 control.orientation.w = 1;
00210 control.orientation.x = 0;
00211 control.orientation.y = 1;
00212 control.orientation.z = 0;
00213 control.name = "rotate_z";
00214 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00215 int_marker.controls.push_back(control);
00216 control.name = "move_z";
00217 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00218 int_marker.controls.push_back(control);
00219
00220 control.orientation.w = 1;
00221 control.orientation.x = 0;
00222 control.orientation.y = 0;
00223 control.orientation.z = 1;
00224 control.name = "rotate_y";
00225 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00226 int_marker.controls.push_back(control);
00227 control.name = "move_y";
00228 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00229 int_marker.controls.push_back(control);
00230 }
00231
00232 int_marker.scale = std::max(object_x_, std::max(object_y_, object_z_)) + 0.5;
00233
00234 server_->insert(int_marker,
00235 boost::bind(&Marker6DOF::processFeedbackCB, this, _1));
00236
00237 menu_handler_.apply(*server_, "marker");
00238 server_->applyChanges();
00239 }
00240
00241 void publishTF(const geometry_msgs::PoseStamped& pose) {
00242 tf::Transform transform;
00243 tf::poseMsgToTF(pose.pose, transform);
00244 tf_broadcaster_->sendTransform(tf::StampedTransform(
00245 transform, pose.header.stamp,
00246 frame_id_,
00247 tf_frame_));
00248 }
00249
00250 void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00251 boost::mutex::scoped_lock lock(mutex_);
00252 geometry_msgs::PoseStamped pose;
00253 pose.header = feedback->header;
00254 pose.pose = feedback->pose;
00255 latest_pose_ = pose;
00256 pose_pub_.publish(pose);
00257 }
00258
00259 void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00260 show_6dof_circle_ = !show_6dof_circle_;
00261 if (show_6dof_circle_) {
00262 menu_handler_.setCheckState(circle_menu_entry_,
00263 interactive_markers::MenuHandler::CHECKED);
00264 }
00265 else {
00266 menu_handler_.setCheckState(circle_menu_entry_,
00267 interactive_markers::MenuHandler::UNCHECKED);
00268 }
00269 initializeInteractiveMarker();
00270 }
00271
00272 void timerCallback(const ros::TimerEvent& e) {
00273 boost::mutex::scoped_lock lock(mutex_);
00274 geometry_msgs::PoseStamped pose = latest_pose_;
00275 pose.header.stamp = e.current_real;
00276 publishTF(pose);
00277 }
00278
00279 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
00280 interactive_markers::MenuHandler menu_handler_;
00281 ros::Subscriber pose_stamped_sub_;
00282 ros::Publisher pose_pub_;
00283 std::string frame_id_;
00284 std::string object_type_;
00285 double object_x_;
00286 double object_y_;
00287 double object_z_;
00288 double object_r_;
00289 double object_g_;
00290 double object_b_;
00291 double object_a_;
00292 double line_width_;
00293 bool show_6dof_circle_;
00294 bool publish_tf_;
00295 std::string tf_frame_;
00296 ros::Timer timer_;
00297 boost::shared_ptr<tf::TransformBroadcaster> tf_broadcaster_;
00298 boost::mutex mutex_;
00299 interactive_markers::MenuHandler::EntryHandle circle_menu_entry_;
00300 geometry_msgs::PoseStamped latest_pose_;
00301 };
00302
00303
00304 int main(int argc, char** argv) {
00305 ros::init(argc, argv, "marker_6dof");
00306 Marker6DOF marker;
00307 ros::spin();
00308 return 0;
00309 }