DetectedObject delegates a detected object from a third-party perception algorithm.
More...
#include <aikido/perception/DetectedObject.hpp>
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".
◆ DetectedObject() [1/2]
aikido::perception::DetectedObject::DetectedObject |
( |
| ) |
|
|
default |
◆ 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] | objectName | Name of the object. |
[in] | objectId | Unique ID for object in Aikido world. |
[in] | detectionFrameID | Frame ID from ROS Marker |
[in] | yamlStr | YAML string which specifies AssetDatabase with {"db_key": key} and additional parameters. |
◆ ~DetectedObject()
virtual aikido::perception::DetectedObject::~DetectedObject |
( |
| ) |
|
|
virtualdefault |
◆ getAssetKey()
std::string aikido::perception::DetectedObject::getAssetKey |
( |
| ) |
const |
◆ 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] | key | The 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 | ) |
|
◆ mAssetKey
std::string aikido::perception::DetectedObject::mAssetKey |
|
private |
◆ 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 |
◆ 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.