HLR  0.0.1
PointCloudNode.hpp
1 #ifndef POINT_CLOUD_NODE_HPP
2 #define POINT_CLOUD_NODE_HPP
3 
4 #include <vector>
5 #include <ros/ros.h>
6 #include <HLR/FullWorld.h> //ROS srv
7 #include <HLR/World.h> //ROS msg
8 #include <std_msgs/Header.h>
9 #include "Object.hpp"
10 #include "ObjectInterpreter.hpp"
11 #include <Vision/ICupDetector.hpp>
12 
13 namespace HLR
14 {
15 namespace PointCloud
16 {
26 {
27 public:
38  explicit PointCloudNode(ros::Rate update_rate);
47  [[noreturn]] void run();
48 
49 private:
50  const ros::Rate update_rate;
51 
52  ros::NodeHandle nh;
53  ros::ServiceServer service;
54  ros::Publisher publisher;
55  ros::Timer timer;
56  ObjectInterpreter interpreter;
57  // TODO: how do we instantiate a CupDetector?
58  std::unique_ptr<HLR::Vision::ICupDetector> cup_detector;
59 
60  void publish_world(const ros::TimerEvent& event);
61 
62  bool service_callback(HLR::FullWorld::Request& request,
63  HLR::FullWorld::Response& response);
68  ros::Time last_data{};
69 };
70 
71 } // namespace PointCloud
72 } // namespace HLR
73 
74 #endif /* POINT_CLOUD_NODE_HPP */
Class responsible for merging the world data from the Kinect and the LiDAR.
Definition: ObjectInterpreter.hpp:19
void run()
Run the pipeline reading data from the Kinect and LiDAR, interpreting it and publishing it on a ROS t...
PointCloudNode(ros::Rate update_rate)
Initialize PointCloudNode.
This class is the main class for the PointCloud namespaces.
Definition: PointCloudNode.hpp:25