Aikido
aikido::perception::DetectedObject Class Reference

DetectedObject delegates a detected object from a third-party perception algorithm. More...

#include <aikido/perception/DetectedObject.hpp>

Public Member Functions

 DetectedObject ()=default
 Default constructor. More...
 
 DetectedObject (const std::string &objectName, const int &objectId, const std::string &detectionFrameID, const std::string &yamlStr)
 Constructs a DetectedObject. More...
 
virtual ~DetectedObject ()=default
 
std::string getUid () const
 Get the unique id of the object. More...
 
std::string getAssetKey () const
 Get the object key for AssetDatabase. More...
 
std::string getDetectionFrameID () const
 Get the detection frame id that refers the origin of this object's pose. More...
 
std::string getName () const
 Get the name of this object. More...
 
YAML::Node getYamlNode ()
 Get the map of keys to additional informations. More...
 
dart::dynamics::MetaSkeletonPtr getMetaSkeleton () const
 Get the metaSkeleton associated with this object. More...
 
void setMetaSkeleton (const dart::dynamics::MetaSkeletonPtr &metaSkeleton)
 Set Metaskeleton. More...
 
template<typename T >
getInfoByKey (const std::string &key) const
 Get a specific value from the information map by a key and the typename of the field. More...
 

Private Attributes

std::string mObjectName
 The name of the object. More...
 
std::string mUid
 The unique id of the object. More...
 
std::string mAssetKey
 The object key for AssetDatabase. More...
 
std::string mDetectionFrameID
 The detection frame id that refers the origin of this object's pose. More...
 
YAML::Node mYamlNode
 The information map with additional information of this object. More...
 
dart::dynamics::MetaSkeletonPtr mMetaSkeleton
 MetaSkeleton associated with this object. More...
 

Detailed Description

DetectedObject delegates a detected object from a third-party perception algorithm.

A perception algorithm should send information for an object via ROS visualization_msgs/Marker message like the following: Marker.ns + "_" + Marker.id -> uid (identity in planner::World) Marker.ns -> object name (e.g. "cantaloupe") Marker.header.frame_id -> detectionFrameID Marker.text -> yamlStr yamlStr contains any additional information in YAML format. It must contain the Asset Database Key using "db_key". (

See also
AssetDatabase for details) Here is an example:
{
"db_key": "food_item",
"score": 0.9,
"success_rates": [0.4, 0.9, 0.1, 0.2],
"strategies": ["vertical_0", "vertical_90", "tilted_0", "tilted_90"],
}
ObjectName may be different from AssetDatabase key, which may be a higher-level description of the object. For example, objectName can be "cantaloupe" while AssetDatabase key is "food_item".

Constructor & Destructor Documentation

◆ DetectedObject() [1/2]

aikido::perception::DetectedObject::DetectedObject ( )
default

Default constructor.

◆ DetectedObject() [2/2]

aikido::perception::DetectedObject::DetectedObject ( const std::string &  objectName,
const int &  objectId,
const std::string &  detectionFrameID,
const std::string &  yamlStr 
)

Constructs a DetectedObject.

Object's Uid is created as objectName_objectID

Parameters
[in]objectNameName of the object.
[in]objectIdUnique ID for object in Aikido world.
[in]detectionFrameIDFrame ID from ROS Marker
[in]yamlStrYAML string which specifies AssetDatabase with {"db_key": key} and additional parameters.

◆ ~DetectedObject()

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

Member Function Documentation

◆ getAssetKey()

std::string aikido::perception::DetectedObject::getAssetKey ( ) const

Get the object key for AssetDatabase.

◆ getDetectionFrameID()

std::string aikido::perception::DetectedObject::getDetectionFrameID ( ) const

Get the detection frame id that refers the origin of this object's pose.

◆ getInfoByKey()

template<typename T >
T aikido::perception::DetectedObject::getInfoByKey ( const std::string &  key) const

Get a specific value from the information map by a key and the typename of the field.

Parameters
[in]keyThe key (string) of a field in the information map Sequence types (e.g. [1, 2]) can be read into standard containers (e.g. std::vector<double>) Map types are not supported with this function. Please get the manually with getYamlNode().

◆ getMetaSkeleton()

dart::dynamics::MetaSkeletonPtr aikido::perception::DetectedObject::getMetaSkeleton ( ) const

Get the metaSkeleton associated with this object.

◆ getName()

std::string aikido::perception::DetectedObject::getName ( ) const

Get the name of this object.

◆ getUid()

std::string aikido::perception::DetectedObject::getUid ( ) const

Get the unique id of the object.

◆ getYamlNode()

YAML::Node aikido::perception::DetectedObject::getYamlNode ( )

Get the map of keys to additional informations.

◆ setMetaSkeleton()

void aikido::perception::DetectedObject::setMetaSkeleton ( const dart::dynamics::MetaSkeletonPtr &  metaSkeleton)

Set Metaskeleton.

Member Data Documentation

◆ mAssetKey

std::string aikido::perception::DetectedObject::mAssetKey
private

The object key for AssetDatabase.

◆ mDetectionFrameID

std::string aikido::perception::DetectedObject::mDetectionFrameID
private

The detection frame id that refers the origin of this object's pose.

◆ mMetaSkeleton

dart::dynamics::MetaSkeletonPtr aikido::perception::DetectedObject::mMetaSkeleton
private

MetaSkeleton associated with this object.

◆ mObjectName

std::string aikido::perception::DetectedObject::mObjectName
private

The name of the object.

◆ mUid

std::string aikido::perception::DetectedObject::mUid
private

The unique id of the object.

◆ mYamlNode

YAML::Node aikido::perception::DetectedObject::mYamlNode
private

The information map with additional information of this object.