Go to the documentation of this file.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
00037
00047
00048 #include <ros/ros.h>
00049
00050 #include "pcl/io/pcd_io.h"
00051 #include "pcl/point_types.h"
00052 #include "pcl/common/common.h"
00053 #include "pcl/ModelCoefficients.h"
00054
00055 #include <tf/transform_listener.h>
00056 #include <geometry_msgs/PoseStamped.h>
00057
00058 using namespace std;
00059
00060 class PointcloudLinePose
00061 {
00062 protected:
00063 ros::NodeHandle nh_;
00064
00065 public:
00066 string output_pose_topic_, input_model_topic_;
00067
00068 ros::Subscriber sub_;
00069 ros::Publisher pub_;
00070
00071 pcl::ModelCoefficients model_in_;
00072
00073 geometry_msgs::PoseStamped handle_pose_;
00074
00075
00076 bool sleep_;
00078 PointcloudLinePose (ros::NodeHandle &n) : nh_(n)
00079 {
00080
00081 nh_.param("input_model_topic", input_model_topic_, std::string("model"));
00082 nh_.param("output_pose_topic", output_pose_topic_, std::string("handle_pose"));
00083 nh_.param("sleep", sleep_, false);
00084
00085 sub_ = nh_.subscribe (input_model_topic_, 10, &PointcloudLinePose::model_cb, this);
00086 ROS_INFO ("[PointcloudLinePose:] Listening for incoming data on topic %s.", nh_.resolveName (input_model_topic_).c_str ());
00087 pub_ = nh_.advertise<geometry_msgs::PoseStamped>(output_pose_topic_, 10);
00088 ROS_INFO ("[PointcloudLinePose:] Will be publishing data on topic %s.", nh_.resolveName (output_pose_topic_).c_str ());
00089 }
00090
00092
00093 void model_cb (const pcl::ModelCoefficientsConstPtr& model)
00094 {
00095 handle_pose_.header = model->header;
00096 handle_pose_.pose.position.x = model->values[0];
00097 handle_pose_.pose.position.y = model->values[1];
00098 handle_pose_.pose.position.z = model->values[2];
00099
00100
00101 btVector3 axis(model->values[3], model->values[4], model->values[5]);
00102 btVector3 marker_axis(1, 0, 0);
00103 btQuaternion qt(marker_axis.cross(axis.normalize()), marker_axis.angle(axis.normalize()));
00104 geometry_msgs::Quaternion quat_msg;
00105 tf::quaternionTFToMsg(qt, quat_msg);
00106 handle_pose_.pose.orientation = quat_msg;
00107 ROS_INFO("[PointcloudLinePose:] Published cluster to topic %s", output_pose_topic_.c_str());
00108 if (sleep_)
00109 sleep(1.0);
00110 pub_.publish (handle_pose_);
00111 }
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137 };
00138
00139 int main (int argc, char** argv)
00140 {
00141 ros::init (argc, argv, "pointcloud_line_pose");
00142 ros::NodeHandle n("~");
00143 PointcloudLinePose lp(n);
00144 ros::spin ();
00145 return (0);
00146 }