6 #include <boost/thread.hpp>
10 #include <sensor_msgs/CameraInfo.h>
11 #include <sensor_msgs/LaserScan.h>
12 #include <sensor_msgs/PointCloud2.h>
14 #include <std_msgs/ByteMultiArray.h>
33 std::shared_ptr<diagnostic_updater::Updater>
updater;
53 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"driver running");
73 sensor_msgs::CameraInfo ci;
87 for (
int i = 0;
i < 9;
i++)
97 for (
int i = 0;
i < 12;
i++)
113 memcpy(m.data, vec.data(), vec.size() *
sizeof(uint16_t));
114 sensor_msgs::ImagePtr
msg =
125 memcpy(m.data, vec.data(), vec.size() *
sizeof(uint16_t));
126 sensor_msgs::ImagePtr
msg =
135 std::vector<uint16_t> vec = dataHandler.
getStateMap();
137 memcpy(m.data, vec.data(), vec.size() *
sizeof(uint16_t));
138 sensor_msgs::ImagePtr
msg =
151 cloudMsg->header =
header;
152 cloudMsg->height = dataHandler.
getHeight();
153 cloudMsg->width = dataHandler.
getWidth();
154 cloudMsg->is_dense =
false;
155 cloudMsg->is_bigendian =
false;
157 cloudMsg->fields.resize(5);
158 cloudMsg->fields[0].name =
"x";
159 cloudMsg->fields[1].name =
"y";
160 cloudMsg->fields[2].name =
"z";
161 cloudMsg->fields[3].name =
"intensity";
163 for (
size_t d = 0;
d < 3; ++
d, offset +=
sizeof(float))
165 cloudMsg->fields[
d].offset = offset;
166 cloudMsg->fields[
d].datatype = int(sensor_msgs::PointField::FLOAT32);
167 cloudMsg->fields[
d].count = 1;
170 cloudMsg->fields[3].offset = offset;
171 cloudMsg->fields[3].datatype = int(sensor_msgs::PointField::UINT16);
172 cloudMsg->fields[3].count = 1;
173 offset +=
sizeof(uint16_t);
175 cloudMsg->point_step = offset;
176 cloudMsg->row_step = cloudMsg->point_step * cloudMsg->width;
177 cloudMsg->data.resize(cloudMsg->height * cloudMsg->row_step);
179 std::vector<PointXYZ> pointCloud;
186 std::vector<uint16_t>::const_iterator itIntens = dataHandler.
getIntensityMap().begin();
187 std::vector<PointXYZ>::const_iterator itPC = pointCloud.begin();
189 for (
size_t index = 0; index < cloudSize; ++index, ++itIntens, ++itPC)
191 memcpy(&cloudMsg->data[index * cloudMsg->point_step + cloudMsg->fields[0].offset], &*itPC,
sizeof(
PointXYZ));
192 memcpy(&cloudMsg->data[index * cloudMsg->point_step + cloudMsg->fields[3].offset], &*itIntens,
sizeof(uint16_t));
199 bool publishedAnything =
false;
207 publishedAnything =
true;
213 publishedAnything =
true;
219 publishedAnything =
true;
225 publishedAnything =
true;
231 publishedAnything =
true;
236 if (publishedAnything)
264 std::shared_ptr<VisionaryTMiniData> pDataHandler)
268 if (!pDataStream->getNextFrame())
279 ROS_INFO(
"skipping frame with number %d", pDataHandler->getFrameNum());
317 int main(
int argc,
char** argv)
319 ros::init(argc, argv,
"sick_visionary_t_mini");
323 std::string remoteDeviceIp =
"192.168.1.10";
333 std::shared_ptr<VisionaryTMiniData> pDataHandler = std::make_shared<VisionaryTMiniData>();
334 std::shared_ptr<VisionaryDataStream> pDataStream = std::make_shared<VisionaryDataStream>(pDataHandler);
335 gControl = std::make_shared<VisionaryControl>();
337 ROS_INFO(
"Connecting to device at %s", remoteDeviceIp.c_str());
338 if (!
gControl->open(VisionaryControl::ProtocolType::COLA_2, remoteDeviceIp.c_str(), 5000 ))
340 ROS_ERROR(
"Connection with devices control channel failed");
346 if (!pDataStream->open(remoteDeviceIp.c_str(), 2114u))
348 ROS_ERROR(
"Connection with devices data channel failed");
353 ROS_INFO(
"Connected with Visionary-T Mini");
391 double min_freq = desiredFreq * 0.9;
392 double max_freq = desiredFreq * 1.1;
427 boost::thread rec_thr(boost::bind(&
thr_receive_frame, pDataStream, pDataHandler));
437 pDataStream->close();