Aikido
PerceptionModule.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PERCEPTION_PERCEPTIONMODULE_HPP_
2 #define AIKIDO_PERCEPTION_PERCEPTIONMODULE_HPP_
3 
4 #include <ros/ros.h>
5 
8 
9 namespace aikido {
10 namespace perception {
11 
17 {
18 public:
19  virtual ~PerceptionModule() = default;
20 
37  virtual bool detectObjects(
38  const aikido::planner::WorldPtr& env,
39  ros::Duration timeout = ros::Duration(),
40  ros::Time timestamp = ros::Time(0.0),
41  std::vector<DetectedObject>* detectedObjects = nullptr)
42  = 0;
43 };
44 
45 } // namespace perception
46 } // namespace aikido
47 
48 #endif // AIKIDO_PERCEPTION_PERCEPTIONMODULE_HPP_
aikido::perception::PerceptionModule
The interface for the generic perception module.
Definition: PerceptionModule.hpp:16
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::WorldPtr
std::shared_ptr< World > WorldPtr
Definition: World.hpp:14
aikido::perception::PerceptionModule::~PerceptionModule
virtual ~PerceptionModule()=default
DetectedObject.hpp
World.hpp
aikido::perception::PerceptionModule::detectObjects
virtual bool detectObjects(const aikido::planner::WorldPtr &env, ros::Duration timeout=ros::Duration(), ros::Time timestamp=ros::Time(0.0), std::vector< DetectedObject > *detectedObjects=nullptr)=0
Run the specific detector via a service call or ROS message reception, lookup the transform between t...