Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <interactive_markers/interactive_marker_server.h>
00003 #include <tf/transform_broadcaster.h>
00004 #include <geometry_msgs/Pose.h>
00005 #include <rosbag/bag.h>
00006
00007 using namespace std;
00008
00009 class InteractiveTF
00010 {
00011 private:
00012 interactive_markers::InteractiveMarkerServer im_server_;
00013 tf::TransformBroadcaster tf_broad_;
00014 std::string parent_frame_, child_frame_;
00015 double rate_;
00016 ros::Timer tf_timer_;
00017 geometry_msgs::Pose marker_pose_;
00018 geometry_msgs::TransformStamped cur_tf_msg;
00019 public:
00020 InteractiveTF(const std::string& parent_frame, const std::string& child_frame, double rate = 100);
00021 void processTFControl(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00022 void addTFMarker();
00023 void publishTF(const ros::TimerEvent& event);
00024 void bagTF(const string& bag_name);
00025 };
00026
00027 InteractiveTF::InteractiveTF(const std::string& parent_frame,
00028 const std::string& child_frame, double rate) :
00029 im_server_("transform_marker"),
00030 parent_frame_(parent_frame),
00031 child_frame_(child_frame),
00032 rate_(rate)
00033 {
00034 marker_pose_.orientation.w = 1;
00035 }
00036
00037 void InteractiveTF::addTFMarker()
00038 {
00039 ros::NodeHandle nh;
00040 visualization_msgs::InteractiveMarker tf_marker;
00041 tf_marker.header.frame_id = "/base_link";
00042 tf_marker.name = "tf_marker";
00043 tf_marker.scale = 0.2;
00044 visualization_msgs::InteractiveMarkerControl tf_control;
00045 tf_control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
00046
00047 tf_control.orientation.x = 1; tf_control.orientation.y = 0;
00048 tf_control.orientation.z = 0; tf_control.orientation.w = 1;
00049 tf_control.name = "rotate_x";
00050 tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00051 tf_marker.controls.push_back(tf_control);
00052 tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00053 tf_marker.controls.push_back(tf_control);
00054
00055 tf_control.orientation.x = 0; tf_control.orientation.y = 1;
00056 tf_control.orientation.z = 0; tf_control.orientation.w = 1;
00057 tf_control.name = "rotate_y";
00058 tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00059 tf_marker.controls.push_back(tf_control);
00060 tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00061 tf_marker.controls.push_back(tf_control);
00062
00063 tf_control.orientation.x = 0; tf_control.orientation.y = 0;
00064 tf_control.orientation.z = 1; tf_control.orientation.w = 1;
00065 tf_control.name = "rotate_z";
00066 tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00067 tf_marker.controls.push_back(tf_control);
00068 tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00069 tf_marker.controls.push_back(tf_control);
00070 im_server_.insert(tf_marker, boost::bind(&InteractiveTF::processTFControl, this, _1));
00071 im_server_.applyChanges();
00072 tf_timer_ = nh.createTimer(ros::Duration(1.0 / rate_), &InteractiveTF::publishTF, this);
00073 }
00074
00075 void InteractiveTF::processTFControl(
00076 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
00077 {
00078 ROS_INFO_STREAM(feedback->pose.position.x << " " <<
00079 feedback->pose.position.y << " " <<
00080 feedback->pose.position.z << " " <<
00081 feedback->pose.orientation.x << " " <<
00082 feedback->pose.orientation.y << " " <<
00083 feedback->pose.orientation.z << " " <<
00084 feedback->pose.orientation.w << " ");
00085 marker_pose_ = feedback->pose;
00086 }
00087
00088 void InteractiveTF::publishTF(const ros::TimerEvent& event)
00089 {
00090 geometry_msgs::TransformStamped tf_msg;
00091 tf_msg.header.stamp = ros::Time::now();
00092 tf_msg.header.frame_id = parent_frame_;
00093 tf_msg.child_frame_id = child_frame_;
00094 tf_msg.transform.translation.x = marker_pose_.position.x;
00095 tf_msg.transform.translation.y = marker_pose_.position.y;
00096 tf_msg.transform.translation.z = marker_pose_.position.z;
00097 tf_msg.transform.rotation.x = marker_pose_.orientation.x;
00098 tf_msg.transform.rotation.y = marker_pose_.orientation.y;
00099 tf_msg.transform.rotation.z = marker_pose_.orientation.z;
00100 tf_msg.transform.rotation.w = marker_pose_.orientation.w;
00101 tf_broad_.sendTransform(tf_msg);
00102 cur_tf_msg = tf_msg;
00103 }
00104
00105 void InteractiveTF::bagTF(const string& bag_name)
00106 {
00107 rosbag::Bag bag;
00108 bag.open(bag_name, rosbag::bagmode::Write);
00109 bag.write("/itf_transform", cur_tf_msg.header.stamp, cur_tf_msg);
00110 bag.close();
00111 }
00112
00113 int main(int argc, char **argv)
00114 {
00115 if(argc != 3 && argc != 4 && argc != 5) {
00116 printf("Usage: interative_tf parent_frame child_frame [rate] [bag_file]\n");
00117 return 1;
00118 }
00119 ros::init(argc, argv, "interactive_tf");
00120 if(argc >= 4) {
00121 InteractiveTF itf(argv[1], argv[2], atof(argv[3]));
00122 itf.addTFMarker();
00123 ros::spin();
00124 if(argc >= 5)
00125 itf.bagTF(argv[4]);
00126 } else {
00127 InteractiveTF itf(argv[1], argv[2]);
00128 itf.addTFMarker();
00129 ros::spin();
00130 }
00131
00132 return 0;
00133 }