ed_sensor_integration
kinect_plugin.cpp
Go to the documentation of this file.
1 #include "kinect_plugin.h"
2 
3 #include <rgbd/image.h>
4 
5 #include <ros/node_handle.h>
6 
7 #include <ed/entity.h>
8 #include <ed/error_context.h>
9 #include <ed/update_request.h>
10 #include <ed/uuid.h>
11 #include <ed/world_model.h>
12 
13 #include <tue/config/reader.h>
14 
15 #include <rgbd/view.h>
16 
17 #include "ed/kinect/association.h"
18 
19 // GetImage
20 #include <rgbd/serialization.h>
22 #include <ed/io/json_writer.h>
24 
26 
27 //#include <opencv2/highgui/highgui.hpp>
28 
29 #include "ray_tracer.h"
30 
31 // ----------------------------------------------------------------------------------------------------
32 
34 {
35  ed::ErrorContext errc("RGBDPlugin", "constructor");
36 }
37 
38 // ----------------------------------------------------------------------------------------------------
39 
41 {
42  ed::ErrorContext errc("RGBDPlugin", "destructor");
43 }
44 
45 // ----------------------------------------------------------------------------------------------------
46 
48 {
49  ed::ErrorContext errc("RGBDPlugin", "initialize");
51 
52  std::string topic;
53  if (config.value("topic", topic))
54  {
55  ROS_INFO_STREAM("[ED KINECT PLUGIN] Initializing kinect client with topic '" << topic << "'.");
56  image_buffer_.initialize(topic, "map");
57  }
58 
59  if (config.readGroup("updater", tue::config::REQUIRED))
60  {
61  updater_ = std::make_unique<Updater>(config.limitScope());
62  config.endGroup();
63  }
64 
65  // - - - - - - - - - - - - - - - - - -
66  // Services
67 
68  ros::NodeHandle nh("~");
69  nh.setCallbackQueue(&cb_queue_);
70 
71  srv_get_image_ = nh.advertiseService("kinect/get_image", &KinectPlugin::srvGetImage, this);
72  srv_update_ = nh.advertiseService("kinect/update", &KinectPlugin::srvUpdate, this);
73  srv_ray_trace_ = nh.advertiseService("ray_trace", &KinectPlugin::srvRayTrace, this);
74 
75  ray_trace_visualization_publisher_ = nh.advertise<visualization_msgs::Marker>("ray_trace_visualization", 10);
76 }
77 
78 // ----------------------------------------------------------------------------------------------------
79 
81 {
82  ed::ErrorContext errc("RGBDPlugin", "process");
83  // - - - - - - - - - - - - - - - - - -
84  // Fetch kinect image and pose
85 
86 // last_image_.reset();
87 // if (!image_buffer_.nextImage("map", last_image_, last_sensor_pose_))
88 // return;
89 
90  // - - - - - - - - - - - - - - - - - -
91  // Check ROS callback queue
92 
93  world_ = &data.world;
94  update_req_ = &req;
95 
96  cb_queue_.callAvailable();
97 
98  // - - - - - - - - - - - - - - - - - -
99 
100 // cv::imshow("kinect", last_image_->getRGBImage());
101 // cv::waitKey(3);
102 }
103 
104 // ----------------------------------------------------------------------------------------------------
105 
106 bool KinectPlugin::srvGetImage(ed_sensor_integration_msgs::GetImage::Request& req, ed_sensor_integration_msgs::GetImage::Response& res)
107 {
108  ed::ErrorContext errc("RGBDPlugin", "srvGetImage");
109  // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
110  // Get new image
111 
113  geo::Pose3D sensor_pose;
114 
115  if (!image_buffer_.waitForRecentImage(image, sensor_pose, 2.0))
116  {
117  res.error_msg = "Could not get image";
118  return true;
119  }
120 
121  // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
122  // Serialize RGBD image
123 
124  std::stringstream stream;
127  tue::serialization::convert(stream, res.rgbd_data);
128 
129  // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
130  // Write meta data
131 
132  std::stringstream meta_data;
133  ed::io::JSONWriter w(meta_data);
134 
135  // Write sensor pose
136  w.writeGroup("sensor_pose");
137  ed::serialize(sensor_pose, w);
138  w.endGroup();
139 
140  // Write rgbd filename
141  w.writeValue("rgbd_filename", req.filename + ".rgbd");
142 
143  // Write timestamp
144  w.writeGroup("timestamp");
145  ed::serializeTimestamp(image->getTimestamp(), w);
146  w.endGroup();
147 
148  w.finish();
149 
150  res.json_meta_data = meta_data.str();
151 
152  ROS_INFO_STREAM("[ED KINECT] Requested image. Image size: " << res.rgbd_data.size()
153  << " bytes. Meta-data size: " << res.json_meta_data.size() << " bytes.");
154 
155  return true;
156 }
157 
158 // ----------------------------------------------------------------------------------------------------
159 
160 bool KinectPlugin::srvUpdate(ed_sensor_integration_msgs::Update::Request& req, ed_sensor_integration_msgs::Update::Response& res)
161 {
162  ed::ErrorContext errc("RGBDPlugin", "srvUpdate");
163  // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
164  // Get new image
165 
167  geo::Pose3D sensor_pose;
168 
169  if (!image_buffer_.waitForRecentImage(image, sensor_pose, 2.0))
170  {
171  res.error_msg = "Could not get image";
172  return true;
173  }
174 
175  // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
176  // Perform update
177 
178  UpdateRequest kinect_update_req;
179  kinect_update_req.area_description = req.area_description;
180  kinect_update_req.background_padding = req.background_padding;
181  kinect_update_req.fit_supporting_entity = req.fit_supporting_entity;
182 
183  // We expect the orientation of the supporting entity to be approximately correct.
184  // Therefore, only allow rotation updates up to 45 degrees (both clock-wise and anti-clock-wise)
185  kinect_update_req.max_yaw_change = 0.25 * M_PI;
186 
187  UpdateResult kinect_update_res(*update_req_);
188  if (!updater_->update(*world_, image, sensor_pose, kinect_update_req, kinect_update_res))
189  {
190  res.error_msg = kinect_update_res.error.str();
191  return true;
192  }
193 
194  // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
195  // Set result
196 
197  for(unsigned int i = 0; i < kinect_update_res.entity_updates.size(); ++i)
198  {
199  EntityUpdate& e_update = kinect_update_res.entity_updates[i];
200  if (e_update.is_new)
201  res.new_ids.push_back(e_update.id.str());
202  else
203  res.updated_ids.push_back(e_update.id.str());
204 
205  // Lock it, such that is won't be cleared by the clearer plugin
206  update_req_->setFlag(e_update.id, "locked");
207  }
208 
209  for(unsigned int i = 0; i < kinect_update_res.removed_entity_ids.size(); ++i)
210  res.deleted_ids.push_back(kinect_update_res.removed_entity_ids[i].str());
211 
212  return true;
213 }
214 
215 // ----------------------------------------------------------------------------------------------------
216 
217 bool KinectPlugin::srvRayTrace(ed_sensor_integration_msgs::RayTrace::Request& req, ed_sensor_integration_msgs::RayTrace::Response& res)
218 {
219  ed::ErrorContext errc("RGBDPlugin", "srvRayTrace");
220  if (req.raytrace_pose.header.frame_id != "/map" && req.raytrace_pose.header.frame_id != "map")
221  {
222  ROS_ERROR("KinectPlugin::srvRayTrace only works with poses expressed in map frame");
223  return false;
224  }
225 
226  geo::Pose3D ray_trace_pose;
227  geo::convert(req.raytrace_pose.pose, ray_trace_pose);
228 
229  ed_ray_tracer::RayTraceResult ray_trace_result = ed_ray_tracer::ray_trace(*world_, ray_trace_pose);
230 
231  if (!ray_trace_result.success_)
232  {
233  ROS_ERROR("ed_ray_tracer::RayTrace failed!");
234  return false;
235  }
236 
237  res.entity_id = ray_trace_result.entity_id_;
238  geo::convert(ray_trace_result.intersection_point_, res.intersection_point.point);
239  res.intersection_point.header.stamp = ros::Time::now();
240  res.intersection_point.header.frame_id = "map";
241 
242  visualization_msgs::Marker marker_msg;
243  marker_msg.header.frame_id = "map";
244  marker_msg.header.stamp = ros::Time::now();
245  marker_msg.action = visualization_msgs::Marker::ADD;
246  marker_msg.color.a = 0.5;
247  marker_msg.lifetime = ros::Duration(10.0);
248  marker_msg.scale.x = 0.05;
249 
250  static int iter = 0;
251  if (++iter % 2 == 0)
252  {
253  marker_msg.color.b = marker_msg.color.r = 1;
254  }
255  else
256  {
257  marker_msg.color.b = marker_msg.color.g = 1;
258  }
259 
260  marker_msg.type = visualization_msgs::Marker::LINE_STRIP;
261 
262  marker_msg.points.push_back(req.raytrace_pose.pose.position);
263  marker_msg.points.push_back(res.intersection_point.point);
264  ray_trace_visualization_publisher_.publish(marker_msg);
265  marker_msg.color.a = marker_msg.color.r = marker_msg.color.g = marker_msg.color.b = 1;
266  marker_msg.scale.x = 0.02;
267  marker_msg.id = 1;
268  ray_trace_visualization_publisher_.publish(marker_msg);
269 
270  //
271  for(ed::WorldModel::const_iterator it = world_->begin(); it != world_->end(); ++it)
272  {
273  const ed::EntityConstPtr& e = *it;
274  if (e->hasFlag("highlighted"))
275  update_req_->removeFlag(e->id(), "highlighted");
276  }
277 
278  //
279  ed::EntityConstPtr highlighted_e = world_->getEntity(res.entity_id);
280  if (highlighted_e)
281  {
282  ROS_INFO("Hit on %s", res.entity_id.c_str());
283  update_req_->setFlag(res.entity_id, "highlighted");
284  ROS_INFO("Setting %s to highlighted", res.entity_id.c_str());
285  }
286 
287  return true;
288 }
289 
290 // ----------------------------------------------------------------------------------------------------
291 
KinectPlugin::update_req_
ed::UpdateRequest * update_req_
Definition: kinect_plugin.h:56
ed::WorldModel::getEntity
EntityConstPtr getEntity(const ed::UUID &id) const
KinectPlugin::srv_ray_trace_
ros::ServiceServer srv_ray_trace_
Definition: kinect_plugin.h:72
uuid.h
ed::io::JSONWriter::writeValue
void writeValue(const std::string &key, const float *fs, std::size_t size)
ed::UpdateRequest
std::string
std::shared_ptr
EntityUpdate
collection structure for laser entities
Definition: kinect/entity_update.h:9
KinectPlugin::updater_
std::unique_ptr< Updater > updater_
Definition: kinect_plugin.h:49
a
void a()
json_writer.h
update_request.h
ED_REGISTER_PLUGIN
#define ED_REGISTER_PLUGIN(Derived)
ed_ray_tracer::RayTraceResult::success_
bool success_
Definition: ray_tracer.h:20
std::vector::size
T size(T... args)
kinect_plugin.h
ray_tracer.h
std::stringstream
KinectPlugin::srvUpdate
bool srvUpdate(ed_sensor_integration_msgs::Update::Request &req, ed_sensor_integration_msgs::Update::Response &res)
Definition: kinect_plugin.cpp:160
reader.h
association.h
ed::io::JSONWriter::writeGroup
void writeGroup(const std::string &name)
geo::Transform3T
tue::serialization::OutputArchive
ed::InitData
ed::InitData::config
tue::Configuration & config
ed::ErrorContext
ed::WorldModel::begin
const_iterator begin() const
UpdateRequest::background_padding
double background_padding
Definition: kinect/updater.h:24
ed::WorldModel::const_iterator
EntityIterator const_iterator
ed_ray_tracer::ray_trace
RayTraceResult ray_trace(const ed::WorldModel &world, const geo::Pose3D &raytrace_pose)
Definition: ray_tracer.cpp:49
ed_ray_tracer::RayTraceResult::intersection_point_
geo::Vector3 intersection_point_
Definition: ray_tracer.h:22
ed::EntityConstPtr
shared_ptr< const Entity > EntityConstPtr
ed::WorldModel::end
const_iterator end() const
std::vector::push_back
T push_back(T... args)
image
cv::Mat image
UpdateResult::entity_updates
std::vector< EntityUpdate > entity_updates
Definition: kinect/updater.h:40
tue::config::ReaderWriter
tue::serialization::convert
void convert(Archive &a, std::vector< unsigned char > &data)
KinectPlugin::ray_trace_visualization_publisher_
ros::Publisher ray_trace_visualization_publisher_
Definition: kinect_plugin.h:76
rgbd::serialize
bool serialize(const Image &image, tue::serialization::OutputArchive &a, RGBStorageType rgb_type=RGB_STORAGE_JPG, DepthStorageType depth_type=DEPTH_STORAGE_PNG)
image.h
KinectPlugin::world_
const ed::WorldModel * world_
Definition: kinect_plugin.h:54
ed::UpdateRequest::setFlag
void setFlag(const UUID &id, const std::string &flag)
rgbd::RGB_STORAGE_JPG
RGB_STORAGE_JPG
tue::config::ReaderWriter::endGroup
bool endGroup()
UpdateResult::error
std::stringstream error
Definition: kinect/updater.h:43
ed_ray_tracer::RayTraceResult
Definition: ray_tracer.h:13
serialization.h
ed::io::JSONWriter::endGroup
void endGroup()
ed_ray_tracer::RayTraceResult::entity_id_
std::string entity_id_
Definition: ray_tracer.h:21
ed::PluginInput
KinectPlugin
Definition: kinect_plugin.h:25
ed::serialize
void serialize(const ConvexHull &ch, ed::io::Writer &w)
req
string req
UpdateRequest::area_description
std::string area_description
Definition: kinect/updater.h:20
EntityUpdate::is_new
bool is_new
Definition: kinect/entity_update.h:12
rgbd::DEPTH_STORAGE_PNG
DEPTH_STORAGE_PNG
KinectPlugin::srvRayTrace
bool srvRayTrace(ed_sensor_integration_msgs::RayTrace::Request &req, ed_sensor_integration_msgs::RayTrace::Response &res)
Definition: kinect_plugin.cpp:217
geo::convert
void convert(const geo::DepthCamera &cam_model, sensor_msgs::CameraInfo &msg)
KinectPlugin::srv_get_image_
ros::ServiceServer srv_get_image_
Definition: kinect_plugin.h:63
KinectPlugin::cb_queue_
ros::CallbackQueue cb_queue_
Definition: kinect_plugin.h:61
UpdateResult::removed_entity_ids
std::vector< ed::UUID > removed_entity_ids
Definition: kinect/updater.h:41
KinectPlugin::~KinectPlugin
~KinectPlugin()
Definition: kinect_plugin.cpp:40
view.h
UpdateRequest::max_yaw_change
double max_yaw_change
Definition: kinect/updater.h:28
tue::config::ReaderWriter::value
bool value(const std::string &name, T &value, RequiredOrOptional opt=REQUIRED)
ed::io::JSONWriter::finish
void finish()
world_model.h
tue::config::ReaderWriter::limitScope
ReaderWriter limitScope() const
UpdateRequest::fit_supporting_entity
bool fit_supporting_entity
Definition: kinect/updater.h:31
ed::io::JSONWriter
KinectPlugin::srv_update_
ros::ServiceServer srv_update_
Definition: kinect_plugin.h:68
UpdateRequest
Definition: kinect/updater.h:15
ed::UpdateRequest::removeFlag
void removeFlag(const UUID &id, const std::string &flag)
rgbd::ImageBuffer::waitForRecentImage
bool waitForRecentImage(rgbd::ImageConstPtr &image, geo::Pose3D &sensor_pose, double timeout_sec, double check_rate)
tue::config::ReaderWriter::readGroup
bool readGroup(const std::string &name, const RequiredOrOptional opt=OPTIONAL)
rgbd::ImageBuffer::initialize
void initialize(const std::string &topic, const std::string &root_frame="map", const float worker_thread_frequency=20)
std::stringstream::str
T str(T... args)
conversions.h
tue::config::REQUIRED
REQUIRED
entity.h
KinectPlugin::image_buffer_
rgbd::ImageBuffer image_buffer_
Definition: kinect_plugin.h:42
ed::Plugin::initialize
virtual void initialize()
KinectPlugin::KinectPlugin
KinectPlugin()
Definition: kinect_plugin.cpp:33
EntityUpdate::id
ed::UUID id
Definition: kinect/entity_update.h:13
KinectPlugin::process
void process(const ed::PluginInput &data, ed::UpdateRequest &req)
Definition: kinect_plugin.cpp:80
error_context.h
ed::UUID::str
const std::string & str() const
msg_conversions.h
KinectPlugin::srvGetImage
bool srvGetImage(ed_sensor_integration_msgs::GetImage::Request &req, ed_sensor_integration_msgs::GetImage::Response &res)
Definition: kinect_plugin.cpp:106
UpdateResult
Definition: kinect/updater.h:36
ed::serializeTimestamp
void serializeTimestamp(double time, ed::io::Writer &w)
config
tue::config::ReaderWriter config