45 #include <sensor_msgs/PointCloud2.h> 47 #include <boost/thread.hpp> 48 #include <sensor_msgs/CameraInfo.h> 49 #include <std_msgs/ByteMultiArray.h> 91 bool published_anything =
false;
93 sensor_msgs::ImagePtr msg;
94 std_msgs::Header header;
99 published_anything =
true;
101 sensor_msgs::CameraInfo ci;
112 for(
int i=0; i<9; i++) ci.K[i]=0;
118 for(
int i=0; i<12; i++)
131 published_anything =
true;
134 msg->header = header;
138 published_anything =
true;
141 msg->header = header;
145 published_anything =
true;
148 msg->header = header;
152 published_anything =
true;
154 typedef sensor_msgs::PointCloud2 PointCloud;
157 PointCloud::Ptr cloud_msg (
new PointCloud);
158 cloud_msg->header = header;
161 cloud_msg->is_dense =
false;
162 cloud_msg->is_bigendian =
false;
164 cloud_msg->fields.resize (5);
165 cloud_msg->fields[0].name =
"x"; cloud_msg->fields[1].name =
"y"; cloud_msg->fields[2].name =
"z";
166 cloud_msg->fields[3].name =
"confidence"; cloud_msg->fields[4].name =
"intensity";
169 for (
size_t d = 0;
d < cloud_msg->fields.size (); ++
d, offset += 4)
171 cloud_msg->fields[
d].offset = offset;
172 cloud_msg->fields[
d].datatype = (
d<3) ?
int(sensor_msgs::PointField::FLOAT32) : int(sensor_msgs::PointField::UINT16);
173 cloud_msg->fields[
d].count = 1;
175 cloud_msg->point_step = offset;
176 cloud_msg->row_step = cloud_msg->point_step * cloud_msg->width;
177 cloud_msg->data.resize (cloud_msg->height * cloud_msg->width * cloud_msg->point_step);
181 uint16_t *pDepth, *pConf, *pInt;
189 for (
int j = 0; j < data.
get_distance().cols; ++j, ++cp)
192 const float bad_point = std::numeric_limits<float>::quiet_NaN();
193 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[0].offset], &bad_point, sizeof (
float));
194 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[1].offset], &bad_point, sizeof (
float));
195 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[2].offset], &bad_point, sizeof (
float));
202 float r2 = (xp * xp + yp * yp);
209 float s0 = std::sqrt(xp*xp + yp*yp + 1.
f) * 1000.f;
212 const float ox = xp * pDepth[j] / s0;
213 const float oy = yp * pDepth[j] / s0;
214 const float oz = pDepth[j] / s0 - f2rc;
216 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[0].offset], &ox, sizeof (
float));
217 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[1].offset], &oy, sizeof (
float));
218 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[2].offset], &oz, sizeof (
float));
221 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[3].offset], &pConf[j], sizeof (uint16_t));
222 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[4].offset], &pInt [j], sizeof (uint16_t));
226 g_pub_points.
publish(cloud_msg);
229 if(!published_anything) {
237 if(!g_control)
return;
251 int main(
int argc,
char **argv) {
257 boost::asio::io_service io_service;
260 std::string remote_device_ip=
"192.168.1.10";
273 boost::thread thr(boost::bind(&boost::asio::io_service::run, &io_service));
280 g_control = &control;
300 g_pub_confidence.shutdown();
304 g_pub_ios.shutdown();
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
image_transport::Publisher g_pub_intensity
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< Driver_3DCS::Data > g_data
void on_frame(const boost::shared_ptr< Driver_3DCS::Data > &data)
void publish_frame(const Driver_3DCS::Data &data)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void _on_new_subscriber()
ros::Publisher g_pub_camera_info
uint32_t getNumSubscribers() const
void on_new_subscriber_it(const image_transport::SingleSubscriberPublisher &pub)
ROSCPP_DECL void spin(Spinner &spinner)
const cv::Mat & get_confidence() const
const CameraParameters & getCameraParameters() const
ros::Publisher g_pub_points
void publish(const sensor_msgs::Image &message) const
SIG_ON_FRAME & getSignal()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
image_transport::Publisher g_pub_depth
const cv::Mat & get_intensity() const
const std::string TYPE_16UC1
image_transport::Publisher g_pub_confidence
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const bool SUPPRESS_INVALID_POINTS
Flag whether invalid points are to be replaced by NaN.
void on_new_subscriber_ros(const ros::SingleSubscriberPublisher &pub)
Driver_3DCS::Control * g_control
uint32_t getNumSubscribers() const
const uint16_t NARE_DISTANCE_VALUE
Distance code for data outside the TOF range.
bool g_publish_all
If true: prevents skipping of frames and publish everything, otherwise use newest data to publish to ...
int main(int argc, char **argv)
const cv::Mat & get_distance() const
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
#define ROSCONSOLE_DEFAULT_NAME