Go to the documentation of this file. 1 #ifndef ED_SENSOR_INTEGRATION_KINECT_PLUGIN_H_
2 #define ED_SENSOR_INTEGRATION_KINECT_PLUGIN_H_
12 #include <ros/service_server.h>
13 #include <ed_sensor_integration_msgs/GetImage.h>
14 #include <ed_sensor_integration_msgs/Update.h>
15 #include <ed_sensor_integration_msgs/RayTrace.h>
18 #include <ros/publisher.h>
19 #include <visualization_msgs/Marker.h>
63 bool srvGetImage(ed_sensor_integration_msgs::GetImage::Request& req, ed_sensor_integration_msgs::GetImage::Response& res);
68 bool srvUpdate(ed_sensor_integration_msgs::Update::Request& req, ed_sensor_integration_msgs::Update::Response& res);
72 bool srvRayTrace(ed_sensor_integration_msgs::RayTrace::Request& req, ed_sensor_integration_msgs::RayTrace::Response& res);
ed::UpdateRequest * update_req_
ros::ServiceServer srv_ray_trace_
bool srvUpdate(ed_sensor_integration_msgs::Update::Request &req, ed_sensor_integration_msgs::Update::Response &res)
ros::Publisher ray_trace_visualization_publisher_
const ed::WorldModel * world_
bool srvRayTrace(ed_sensor_integration_msgs::RayTrace::Request &req, ed_sensor_integration_msgs::RayTrace::Response &res)
ros::ServiceServer srv_get_image_
ros::CallbackQueue cb_queue_
ros::ServiceServer srv_update_
rgbd::ImageBuffer image_buffer_
virtual void initialize()
void process(const ed::PluginInput &data, ed::UpdateRequest &req)
bool srvGetImage(ed_sensor_integration_msgs::GetImage::Request &req, ed_sensor_integration_msgs::GetImage::Response &res)