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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/interactive_cuboid_likelihood.h"
00038 #include "jsk_pcl_ros/pcl_conversion_util.h"
00039
00040 namespace jsk_pcl_ros
00041 {
00042 void InteractiveCuboidLikelihood::onInit()
00043 {
00044 DiagnosticNodelet::onInit();
00045 tf_ = TfListenerSingleton::getInstance();
00046 pub_ = pnh_->advertise<std_msgs::Float32>("output", 1);
00047 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00048 pnh_->param("frame_id", frame_id_, std::string("odom"));
00049 pnh_->param("sensor_frame", sensor_frame_, std::string("odom"));
00050 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00051 boost::bind (&InteractiveCuboidLikelihood::configCallback, this, _1, _2);
00052 srv_->setCallback (f);
00053 sub_ = pnh_->subscribe("input", 1, &InteractiveCuboidLikelihood::likelihood, this);
00054
00055 server_.reset(new interactive_markers::InteractiveMarkerServer(getName()));
00056 visualization_msgs::InteractiveMarker int_marker = particleToInteractiveMarker(particle_);
00057 server_->insert(int_marker, boost::bind(&InteractiveCuboidLikelihood::processFeedback, this, _1));
00058 server_->applyChanges();
00059
00060
00061 plane_server_.reset(new interactive_markers::InteractiveMarkerServer(getName() + "_plane"));
00062 plane_pose_ = Eigen::Affine3f::Identity();
00063 visualization_msgs::InteractiveMarker plane_int_marker = planeInteractiveMarker();
00064 plane_server_->insert(plane_int_marker, boost::bind(&InteractiveCuboidLikelihood::processPlaneFeedback, this, _1));
00065 plane_server_->applyChanges();
00066 }
00067
00068 void InteractiveCuboidLikelihood::subscribe()
00069 {
00070
00071 }
00072
00073 void InteractiveCuboidLikelihood::unsubscribe()
00074 {
00075
00076 }
00077
00078 void InteractiveCuboidLikelihood::processFeedback(
00079 const visualization_msgs::InteractiveMarkerFeedback::ConstPtr& feedback)
00080 {
00081 boost::mutex::scoped_lock lock(mutex_);
00082 Eigen::Affine3f pose;
00083 tf::poseMsgToEigen(feedback->pose, pose);
00084 particle_.fromEigen(pose);
00085 }
00086
00087 void InteractiveCuboidLikelihood::processPlaneFeedback(
00088 const visualization_msgs::InteractiveMarkerFeedback::ConstPtr& feedback)
00089 {
00090 boost::mutex::scoped_lock lock(mutex_);
00091 tf::poseMsgToEigen(feedback->pose, plane_pose_);
00092 }
00093
00094 void InteractiveCuboidLikelihood::likelihood(
00095 const sensor_msgs::PointCloud2::ConstPtr& msg)
00096 {
00097 boost::mutex::scoped_lock lock(mutex_);
00098 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00099 pcl::fromROSMsg(*msg, *cloud);
00100 tf::StampedTransform transform
00101 = lookupTransformWithDuration(tf_, sensor_frame_, msg->header.frame_id,
00102 ros::Time(0.0),
00103 ros::Duration(0.0));
00104 Eigen::Vector3f vp;
00105 tf::vectorTFToEigen(transform.getOrigin(), vp);
00106 Vertices vertices;
00107 vertices.push_back(Eigen::Vector3f(plane_pose_ * (Eigen::Vector3f::UnitX() + Eigen::Vector3f::UnitY())));
00108 vertices.push_back(Eigen::Vector3f(plane_pose_ * (- Eigen::Vector3f::UnitX() + Eigen::Vector3f::UnitY())));
00109 vertices.push_back(Eigen::Vector3f(plane_pose_ * (- Eigen::Vector3f::UnitX() - Eigen::Vector3f::UnitY())));
00110 vertices.push_back(Eigen::Vector3f(plane_pose_ * (Eigen::Vector3f::UnitX() - Eigen::Vector3f::UnitY())));
00111 Polygon::Ptr plane(new Polygon(vertices));
00112
00113 particle_.plane_index = 0;
00114 std::vector<Polygon::Ptr> polygons;
00115 polygons.push_back(plane);
00116
00117
00118
00119 pcl::KdTreeFLANN<pcl::PointXYZ> tree;
00120 tree.setInputCloud(cloud);
00121 std::vector<float> polygon_likelihood(1, 1.0);
00122 double l = computeLikelihood(particle_, cloud, tree, vp, polygons, polygon_likelihood, config_);
00123 NODELET_INFO("likelihood: %f", l);
00124 std_msgs::Float32 float_msg;
00125 float_msg.data = l;
00126 pub_.publish(float_msg);
00127 }
00128
00129 void InteractiveCuboidLikelihood::configCallback(
00130 Config& config, uint32_t level)
00131 {
00132 boost::mutex::scoped_lock lock(mutex_);
00133 config_ = config;
00134 particle_.dx = config_.dx;
00135 particle_.dy = config_.dy;
00136 particle_.dz = config_.dz;
00137 if (server_) {
00138 visualization_msgs::InteractiveMarker int_marker = particleToInteractiveMarker(particle_);
00139 server_->insert(int_marker, boost::bind(&InteractiveCuboidLikelihood::processFeedback, this, _1));
00140 server_->applyChanges();
00141 }
00142 }
00143
00144 visualization_msgs::InteractiveMarker
00145 InteractiveCuboidLikelihood::planeInteractiveMarker()
00146 {
00147 visualization_msgs::InteractiveMarker int_marker;
00148 int_marker.header.frame_id = frame_id_;
00149 int_marker.header.stamp = ros::Time::now();
00150 int_marker.name = getName() + "_plane";
00151 visualization_msgs::InteractiveMarkerControl control;
00152 control.orientation.w = 1;
00153 control.orientation.x = 1;
00154 control.orientation.y = 0;
00155 control.orientation.z = 0;
00156 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00157 int_marker.controls.push_back(control);
00158 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00159 int_marker.controls.push_back(control);
00160
00161 control.orientation.w = 1;
00162 control.orientation.x = 0;
00163 control.orientation.y = 1;
00164 control.orientation.z = 0;
00165 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00166 int_marker.controls.push_back(control);
00167 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00168 int_marker.controls.push_back(control);
00169
00170 control.orientation.w = 1;
00171 control.orientation.x = 0;
00172 control.orientation.y = 0;
00173 control.orientation.z = 1;
00174 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00175 int_marker.controls.push_back(control);
00176 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00177 int_marker.controls.push_back(control);
00178 visualization_msgs::InteractiveMarkerControl box_control;
00179 box_control.always_visible = true;
00180 visualization_msgs::Marker plane_marker;
00181 plane_marker.type = visualization_msgs::Marker::CUBE;
00182 plane_marker.scale.x = 1.0;
00183 plane_marker.scale.y = 1.0;
00184 plane_marker.scale.z = 0.01;
00185 plane_marker.color.r = 1.0;
00186 plane_marker.color.a = 1.0;
00187 plane_marker.pose.orientation.w = 1.0;
00188 box_control.markers.push_back(plane_marker);
00189 int_marker.controls.push_back(box_control);
00190 return int_marker;
00191 }
00192
00193 visualization_msgs::Marker
00194 InteractiveCuboidLikelihood::particleToMarker(
00195 const Particle& p)
00196 {
00197 visualization_msgs::Marker marker;
00198 marker.type = visualization_msgs::Marker::CUBE;
00199 marker.scale.x = p.dx;
00200 marker.scale.y = p.dy;
00201 marker.scale.z = p.dz;
00202 marker.pose.orientation.w = 1.0;
00203 marker.color.r = 0.5;
00204 marker.color.g = 0.5;
00205 marker.color.b = 0.5;
00206 marker.color.a = 1.0;
00207 return marker;
00208 }
00209
00210 visualization_msgs::InteractiveMarker InteractiveCuboidLikelihood::particleToInteractiveMarker(const Particle& p)
00211 {
00212 visualization_msgs::InteractiveMarker int_marker;
00213 int_marker.header.frame_id = frame_id_;
00214 int_marker.header.stamp = ros::Time::now();
00215 int_marker.name = getName();
00216 Eigen::Affine3f pose = particle_.toEigenMatrix();
00217 tf::poseEigenToMsg(pose, int_marker.pose);
00218
00219 visualization_msgs::InteractiveMarkerControl control;
00220 control.orientation.w = 1;
00221 control.orientation.x = 1;
00222 control.orientation.y = 0;
00223 control.orientation.z = 0;
00224 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00225 int_marker.controls.push_back(control);
00226 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00227 int_marker.controls.push_back(control);
00228
00229 control.orientation.w = 1;
00230 control.orientation.x = 0;
00231 control.orientation.y = 1;
00232 control.orientation.z = 0;
00233 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00234 int_marker.controls.push_back(control);
00235 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00236 int_marker.controls.push_back(control);
00237
00238 control.orientation.w = 1;
00239 control.orientation.x = 0;
00240 control.orientation.y = 0;
00241 control.orientation.z = 1;
00242 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00243 int_marker.controls.push_back(control);
00244 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00245 int_marker.controls.push_back(control);
00246 visualization_msgs::InteractiveMarkerControl box_control;
00247 box_control.always_visible = true;
00248 box_control.markers.push_back(particleToMarker(particle_));
00249 int_marker.controls.push_back(box_control);
00250 return int_marker;
00251 }
00252
00253
00254
00255 }
00256
00257 #include <pluginlib/class_list_macros.h>
00258 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::InteractiveCuboidLikelihood, nodelet::Nodelet);