43 #include <moveit/robot_model_loader/robot_model_loader.h> 45 #include <eigen3/Eigen/Eigen> 50 using namespace boost;
67 private_nh.
param(
"queue_size", queue_size_, 1);
68 private_nh.
param(
"near_clipping_plane_distance", near_clipping_plane_distance_, 0.4);
69 private_nh.
param(
"far_clipping_plane_distance", far_clipping_plane_distance_, 5.0);
71 private_nh.
param(
"shadow_threshold", shadow_threshold_, 0.3);
72 private_nh.
param(
"padding_scale", padding_scale_, 1.0);
73 private_nh.
param(
"padding_offset", padding_offset_, 0.005);
74 double tf_update_rate = 30;
75 private_nh.
param(
"tf_update_rate", tf_update_rate, 30.0);
76 transform_provider_.setUpdateInterval(
long(1000000.0 / tf_update_rate));
81 lock_guard<mutex> lock(connect_mutex_);
82 pub_filtered_depth_image_ =
83 filtered_depth_transport_->advertiseCamera(
"/filtered/depth", queue_size_, itssc, itssc, rssc, rssc);
84 pub_filtered_label_image_ =
85 filtered_label_transport_->advertiseCamera(
"/filtered/labels", queue_size_, itssc, itssc, rssc, rssc);
86 pub_model_depth_image_ =
87 model_depth_transport_->advertiseCamera(
"/model/depth", queue_size_, itssc, itssc, rssc, rssc);
88 pub_model_label_image_ =
89 model_depth_transport_->advertiseCamera(
"/model/label", queue_size_, itssc, itssc, rssc, rssc);
99 mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_);
100 mesh_filter_->setShadowThreshold(shadow_threshold_);
101 mesh_filter_->setPaddingOffset(padding_offset_);
102 mesh_filter_->setPaddingScale(padding_scale_);
104 addMeshes(*mesh_filter_);
105 transform_provider_.start();
109 const sensor_msgs::CameraInfoConstPtr& info_msg)
111 transform_provider_.setFrame(depth_msg->header.frame_id);
114 params.
setCameraParameters(info_msg->K[0], info_msg->K[4], info_msg->K[2], info_msg->K[5]);
115 params.
setImageSize(depth_msg->width, depth_msg->height);
117 const float* src = (
const float*)&depth_msg->data[0];
119 static unsigned dataSize = 0;
120 static unsigned short* data = 0;
121 if (dataSize < depth_msg->width * depth_msg->height)
122 data =
new unsigned short[depth_msg->width * depth_msg->height];
123 for (
unsigned idx = 0; idx < depth_msg->width * depth_msg->height; ++idx)
124 data[idx] = (
unsigned short)(src[idx] * 1000.0);
126 mesh_filter_->filter(data, GL_UNSIGNED_SHORT);
131 if (pub_filtered_depth_image_.getNumSubscribers() > 0)
134 filtered_depth_ptr_->header = depth_msg->header;
136 if (filtered_depth_ptr_->image.cols != depth_msg->width || filtered_depth_ptr_->image.rows != depth_msg->height)
137 filtered_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1);
138 mesh_filter_->getFilteredDepth((
float*)filtered_depth_ptr_->image.data);
139 pub_filtered_depth_image_.publish(filtered_depth_ptr_->toImageMsg(), info_msg);
143 if (pub_model_depth_image_.getNumSubscribers() > 0)
146 model_depth_ptr_->header = depth_msg->header;
148 if (model_depth_ptr_->image.cols != depth_msg->width || model_depth_ptr_->image.rows != depth_msg->height)
149 model_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1);
150 mesh_filter_->getModelDepth((
float*)model_depth_ptr_->image.data);
151 pub_model_depth_image_.publish(model_depth_ptr_->toImageMsg(), info_msg);
154 if (pub_filtered_label_image_.getNumSubscribers() > 0)
157 filtered_label_ptr_->header = depth_msg->header;
159 if (filtered_label_ptr_->image.cols != depth_msg->width || filtered_label_ptr_->image.rows != depth_msg->height)
160 filtered_label_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_8UC4);
161 mesh_filter_->getFilteredLabels((
unsigned int*)filtered_label_ptr_->image.data);
162 pub_filtered_label_image_.publish(filtered_label_ptr_->toImageMsg(), info_msg);
165 if (pub_model_label_image_.getNumSubscribers() > 0)
168 model_label_ptr_->header = depth_msg->header;
169 if (model_label_ptr_->image.cols != depth_msg->width || model_label_ptr_->image.rows != depth_msg->height)
170 model_label_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_8UC4);
171 mesh_filter_->getModelLabels((
unsigned int*)model_label_ptr_->image.data);
172 pub_model_label_image_.publish(model_label_ptr_->toImageMsg(), info_msg);
178 robot_model_loader::RobotModelLoader robotModelLoader(
"robot_description");
179 robot_model::RobotModelConstPtr robotModel = robotModelLoader.getModel();
180 const vector<robot_model::LinkModel*>& links = robotModel->getLinkModelsWithCollisionGeometry();
181 for (
size_t i = 0; i < links.size(); ++i)
188 transform_provider_.addHandle(mesh_handle, links[i]->
getName());
196 lock_guard<mutex> lock(connect_mutex_);
197 if (pub_filtered_depth_image_.getNumSubscribers() == 0 && pub_filtered_label_image_.getNumSubscribers() == 0 &&
198 pub_model_depth_image_.getNumSubscribers() == 0 && pub_model_label_image_.getNumSubscribers() == 0)
200 sub_depth_image_.shutdown();
202 else if (!sub_depth_image_)
206 input_depth_transport_->subscribeCamera(
"depth", queue_size_, &DepthSelfFiltering::depthCb,
this, hints);
211 const sensor_msgs::CameraInfoConstPtr& info_msg)
213 filter(depth_msg, info_msg);
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where...
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string getName(void *handle)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
MeshHandle addMesh(const shapes::Mesh &mesh)
adds a mesh to the filter object.
void filter(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
main filtering routine
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Callback for subscribed depth images.
static const StereoCameraModel::Parameters & RegisteredPSDKParams
predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) ...
Parameters for Stereo-like devices.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
void setCameraParameters(float fx, float fy, float cx, float cy)
sets the camera parameters of the pinhole camera where the disparities were obtained. Usually the left camera
virtual void onInit()
Nodelet init callback.
void setImageSize(unsigned width, unsigned height)
sets the image size
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void connectCb()
Callback for connection/deconnection of listener.
void addMeshes(mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > &mesh_filter)
adding the meshes to a given mesh filter object.
std::shared_ptr< const Shape > ShapeConstPtr