interactive_ellipse.cpp
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 <hrl_ellipsoidal_control/EllipsoidParams.h>
00006 #include <hrl_ellipsoidal_control/LoadEllipsoidParams.h>
00007 //#include <hrl_ellipsoidal_control/utils.h>
00008 
00009 class InteractiveEllipse 
00010 {
00011 private:
00012     interactive_markers::InteractiveMarkerServer im_server_;
00013     tf::TransformBroadcaster tf_broad_;
00014     ros::Publisher params_pub;
00015     ros::Subscriber params_cmd;
00016     std::string parent_frame_, child_frame_;
00017     double rate_;
00018     ros::Timer tf_timer_;
00019     geometry_msgs::Pose marker_pose_;
00020     double z_axis_, y_axis_, old_z_axis_, old_y_axis_;
00021     geometry_msgs::Transform old_marker_tf_;
00022     geometry_msgs::TransformStamped tf_msg_;
00023     hrl_ellipsoidal_control::EllipsoidParams cur_e_params_;
00024     ros::ServiceServer load_param_srv_;
00025 public:
00026     InteractiveEllipse(const std::string& parent_frame, const std::string& child_frame, double rate = 100);
00027     void processTFControl(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00028     void processEllipseControlY(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00029     void processEllipseControlZ(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
00030     void addTFMarker(const geometry_msgs::Transform& mkr_tf);
00031     void addEllipseMarker();
00032     void publishTF(const ros::TimerEvent& event);
00033     void loadEllipsoidParams(const hrl_ellipsoidal_control::EllipsoidParams& e_params);
00034     void bagTF(const string& bag_name);
00035     bool loadParamCB(hrl_ellipsoidal_control::LoadEllipsoidParams::Request& req,
00036                      hrl_ellipsoidal_control::LoadEllipsoidParams::Response& resp);
00037 };
00038 
00039 InteractiveEllipse::InteractiveEllipse(const std::string& parent_frame, 
00040                                        const std::string& child_frame, double rate) :
00041     im_server_("transform_marker"),
00042     parent_frame_(parent_frame),
00043     child_frame_(child_frame),
00044     rate_(rate), z_axis_(0.0), y_axis_(0.0) 
00045     {
00046     ros::NodeHandle nh;
00047     marker_pose_.orientation.w = 1;
00048     params_pub = nh.advertise<hrl_ellipsoidal_control::EllipsoidParams>("/ellipsoid_params", 1);
00049     params_cmd = nh.subscribe("/ell_params_cmd", 1, &InteractiveEllipse::loadEllipsoidParams, this);
00050     load_param_srv_ = nh.advertiseService("/load_ellipsoid_params", 
00051                                           &InteractiveEllipse::loadParamCB, this);
00052 }
00053 
00054 void InteractiveEllipse::addTFMarker(const geometry_msgs::Transform& mkr_tf) 
00055 {
00056     ros::NodeHandle nh;
00057     visualization_msgs::InteractiveMarker tf_marker;
00058     tf_marker.header.frame_id = parent_frame_;
00059     tf_marker.pose.position.x = mkr_tf.translation.x;
00060     tf_marker.pose.position.y = mkr_tf.translation.y;
00061     tf_marker.pose.position.z = mkr_tf.translation.z;
00062     tf_marker.pose.orientation.x = mkr_tf.rotation.x;
00063     tf_marker.pose.orientation.y = mkr_tf.rotation.y;
00064     tf_marker.pose.orientation.z = mkr_tf.rotation.z;
00065     tf_marker.pose.orientation.w = mkr_tf.rotation.w;
00066     tf_marker.name = "tf_marker";
00067     tf_marker.scale = 0.2;
00068     visualization_msgs::InteractiveMarkerControl tf_control;
00069     tf_control.orientation_mode = visualization_msgs::InteractiveMarkerControl::INHERIT;
00070     // x
00071     tf_control.orientation.x = 1; tf_control.orientation.y = 0;
00072     tf_control.orientation.z = 0; tf_control.orientation.w = 1;
00073     tf_control.name = "rotate_x";
00074     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00075     tf_marker.controls.push_back(tf_control);
00076     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00077     tf_marker.controls.push_back(tf_control);
00078     // y
00079     tf_control.orientation.x = 0; tf_control.orientation.y = 1;
00080     tf_control.orientation.z = 0; tf_control.orientation.w = 1;
00081     tf_control.name = "rotate_y";
00082     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00083     tf_marker.controls.push_back(tf_control);
00084     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00085     tf_marker.controls.push_back(tf_control);
00086     // z
00087     tf_control.orientation.x = 0; tf_control.orientation.y = 0;
00088     tf_control.orientation.z = 1; tf_control.orientation.w = 1;
00089     tf_control.name = "rotate_z";
00090     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00091     tf_marker.controls.push_back(tf_control);
00092     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00093     tf_marker.controls.push_back(tf_control);
00094     im_server_.insert(tf_marker, boost::bind(&InteractiveEllipse::processTFControl, this, _1));
00095     im_server_.applyChanges();
00096     tf_timer_ = nh.createTimer(ros::Duration(1.0 / rate_), &InteractiveEllipse::publishTF, this);
00097 }
00098 
00099 void InteractiveEllipse::processTFControl(
00100         const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) 
00101         {
00102     ROS_INFO_STREAM(tf_msg_.transform.translation.x << " " << 
00103                     tf_msg_.transform.translation.y << " " <<
00104                     tf_msg_.transform.translation.z << " " <<
00105                     tf_msg_.transform.rotation.x << " " <<
00106                     tf_msg_.transform.rotation.y << " " <<
00107                     tf_msg_.transform.rotation.z << " " <<
00108                     tf_msg_.transform.rotation.w);
00109     marker_pose_ = feedback->pose;
00110 }
00111 
00112 void InteractiveEllipse::addEllipseMarker() 
00113 {
00114     visualization_msgs::InteractiveMarker tf_marker;
00115     tf_marker.header.frame_id = child_frame_;
00116     tf_marker.name = "ellipse_marker_y";
00117     tf_marker.scale = 0.4;
00118     visualization_msgs::InteractiveMarkerControl tf_control;
00119     tf_control.orientation_mode = visualization_msgs::InteractiveMarkerControl::INHERIT;
00120     // y
00121     tf_control.orientation.x = 0; tf_control.orientation.y = 1;
00122     tf_control.orientation.z = 0; tf_control.orientation.w = 1;
00123     tf_control.name = "shift_y";
00124     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00125     tf_marker.controls.push_back(tf_control);
00126     im_server_.insert(tf_marker, boost::bind(&InteractiveEllipse::processEllipseControlY, this, _1));
00127     tf_marker.controls.clear();
00128     // z
00129     tf_marker.name = "ellipse_marker_z";
00130     tf_control.orientation.x = 0; tf_control.orientation.y = 0;
00131     tf_control.orientation.z = 1; tf_control.orientation.w = 1;
00132     tf_control.name = "shift_z";
00133     tf_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00134     tf_marker.controls.push_back(tf_control);
00135     im_server_.insert(tf_marker, boost::bind(&InteractiveEllipse::processEllipseControlZ, this, _1));
00136     im_server_.applyChanges();
00137 }
00138 
00139 void InteractiveEllipse::processEllipseControlY(
00140         const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) 
00141         {
00142     z_axis_ = feedback->pose.position.z;
00143 }
00144 
00145 void InteractiveEllipse::processEllipseControlZ(
00146         const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) 
00147         {
00148     y_axis_ = feedback->pose.position.y;
00149 }
00150 
00151 void InteractiveEllipse::publishTF(const ros::TimerEvent& event) 
00152 {
00153     tf_msg_.header.stamp = ros::Time::now();
00154     tf_msg_.header.frame_id = parent_frame_;
00155     tf_msg_.child_frame_id = child_frame_;
00156     tf_msg_.transform.translation.x = marker_pose_.position.x;
00157     tf_msg_.transform.translation.y = marker_pose_.position.y;
00158     tf_msg_.transform.translation.z = marker_pose_.position.z;
00159     tf_msg_.transform.rotation.x = marker_pose_.orientation.x;
00160     tf_msg_.transform.rotation.y = marker_pose_.orientation.y;
00161     tf_msg_.transform.rotation.z = marker_pose_.orientation.z;
00162     tf_msg_.transform.rotation.w = marker_pose_.orientation.w;
00163     tf::Transform cur_tf, old_tf;
00164     tf::transformMsgToTF(tf_msg_.transform, cur_tf);
00165     tf::transformMsgToTF(old_marker_tf_, old_tf);
00166     Eigen::Affine3d cur_tf_eig, old_tf_eig;
00167     tf::TransformTFToEigen(cur_tf, cur_tf_eig);
00168     tf::TransformTFToEigen(old_tf, old_tf_eig);
00169     cur_tf_eig = cur_tf_eig;
00170     tf::TransformEigenToTF(cur_tf_eig, cur_tf);
00171     tf::transformTFToMsg(cur_tf, tf_msg_.transform);
00172     tf_broad_.sendTransform(tf_msg_);
00173     hrl_ellipsoidal_control::EllipsoidParams e_params;
00174     e_params.e_frame = tf_msg_;
00175     e_params.height = y_axis_ + old_y_axis_;
00176     e_params.E = z_axis_ + old_z_axis_;
00177     params_pub.publish(e_params);
00178     cur_e_params_ = e_params;
00179 }
00180 
00181 void InteractiveEllipse::loadEllipsoidParams(const hrl_ellipsoidal_control::EllipsoidParams& e_params) 
00182 {
00183     geometry_msgs::Pose pose, empty_pose;
00184     pose.position.x = e_params.e_frame.transform.translation.x;
00185     pose.position.y = e_params.e_frame.transform.translation.y;
00186     pose.position.z = e_params.e_frame.transform.translation.z;
00187     pose.orientation.x = e_params.e_frame.transform.rotation.x;
00188     pose.orientation.y = e_params.e_frame.transform.rotation.y;
00189     pose.orientation.z = e_params.e_frame.transform.rotation.z;
00190     pose.orientation.w = e_params.e_frame.transform.rotation.w;
00191     marker_pose_ = pose;
00192     empty_pose.orientation.w = 1;
00193     im_server_.setPose("tf_marker", pose);
00194     im_server_.setPose("ellipse_marker_y", empty_pose);
00195     im_server_.setPose("ellipse_marker_z", empty_pose);
00196     im_server_.applyChanges();
00197 
00198     old_y_axis_ = e_params.height;
00199     old_z_axis_ = e_params.E;
00200 }
00201 
00202 void InteractiveEllipse::bagTF(const string& bag_name) 
00203 {
00204     rosbag::Bag bag;
00205     bag.open(bag_name, rosbag::bagmode::Write);
00206     bag.write("/ellipsoid_params", ros::Time::now(), cur_e_params_);
00207     bag.close();
00208 }
00209 
00210 bool InteractiveEllipse::loadParamCB(hrl_ellipsoidal_control::LoadEllipsoidParams::Request& req,
00211                                      hrl_ellipsoidal_control::LoadEllipsoidParams::Response& resp)
00212 {
00213     loadEllipsoidParams(req.params);
00214     return true;
00215 }
00216 
00217 int main(int argc, char **argv)
00218 {
00219     ros::init(argc, argv, "interative_ellipse");
00220     if(argc < 3 || argc > 7) {
00221         printf("Usage: interative_ellipse parent_frame child_frame rate [inital_params] [remove_ells]\n");
00222         return 1;
00223     }
00224     if(argc >= 4) {
00225         InteractiveEllipse itf(argv[1], argv[2], atof(argv[3]));
00226         geometry_msgs::Transform mkr_tf;
00227         mkr_tf.rotation.w = 1;
00228         itf.addTFMarker(mkr_tf);
00229         if(!(argc >= 7 && atoi(argv[6])))
00230             itf.addEllipseMarker();
00231         if(argc >= 6) {
00232             // load params
00233             std::vector<hrl_ellipsoidal_control::EllipsoidParams::Ptr> params;
00234             readBagTopic<hrl_ellipsoidal_control::EllipsoidParams>(argv[5], params, "/ellipsoid_params");
00235             itf.loadEllipsoidParams(*params[0]);
00236         }
00237         ros::spin();
00238         if(argc >= 5)
00239             itf.bagTF(argv[4]);
00240     } 
00241 
00242     return 0;
00243 }


hrl_ellipsoidal_control
Author(s): Kelsey Hawkins
autogenerated on Wed Nov 27 2013 11:41:49