Aikido
aikido::perception::PerceptionModule Class Referenceabstract

The interface for the generic perception module. More...

#include <aikido/perception/PerceptionModule.hpp>

Inheritance diagram for aikido::perception::PerceptionModule:
aikido::perception::PoseEstimatorModule

Public Member Functions

virtual ~PerceptionModule ()=default
 
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 the specified frames, load object models for new objects, compute their pose, and update the list of DART Skeletons that represents the world. More...
 

Detailed Description

The interface for the generic perception module.

Provides a detectObjects() method for detecting all objects in the environment and updating the world representation accordingly.

Constructor & Destructor Documentation

◆ ~PerceptionModule()

virtual aikido::perception::PerceptionModule::~PerceptionModule ( )
virtualdefault

Member Function Documentation

◆ detectObjects()

virtual bool aikido::perception::PerceptionModule::detectObjects ( const aikido::planner::WorldPtr env,
ros::Duration  timeout = ros::Duration(),
ros::Time  timestamp = ros::Time(0.0),
std::vector< DetectedObject > *  detectedObjects = nullptr 
)
pure virtual

Run the specific detector via a service call or ROS message reception, lookup the transform between the specified frames, load object models for new objects, compute their pose, and update the list of DART Skeletons that represents the world.

Parameters
[in]envWorld to add perceived objects to.
[in]timeoutThe duration up to which to wait for the transform. Returns false if none of the markers get correctly transformed
[in]timestampOnly detections more recent than this timestamp will be accepted. A timestamp of 0 greedily takes the first available message, and is the default behaviour.
[out]detectedObjectsAn output vector for detected objects before timeout.
Returns
Returns false if no detection observed before timeout. Returns true otherwise.

Implemented in aikido::perception::PoseEstimatorModule.