WorldModel class provides services for adding the viewports of the next best views to a list and retrieve them. Additionally, it provides services for adding objects, detected by object localization and retrieve them.
More...
#include <found_object_handler.hpp>
WorldModel class provides services for adding the viewports of the next best views to a list and retrieve them. Additionally, it provides services for adding objects, detected by object localization and retrieve them.
Definition at line 60 of file found_object_handler.hpp.
bool world_model::FoundObjectHandler::evaluateNeighborhood |
( |
const asr_msgs::AsrObject & |
object1, |
|
|
const asr_msgs::AsrObject & |
object2 |
|
) |
| const |
|
private |
Determines if two objects are neighbors to each other in terms of position and orientation distance.
- Parameters
-
- Returns
- returns true if the two objects are neighbors
Definition at line 160 of file found_object_handler.cpp.
static const std::string world_model::FoundObjectHandler::GetEmptyFoundObjectListServiceName |
( |
| ) |
|
|
inlinestatic |
static const std::string world_model::FoundObjectHandler::GetGetFoundObjectListServiceName |
( |
| ) |
|
|
inlinestatic |
static const std::string world_model::FoundObjectHandler::GetPushFoundObjectListServiceName |
( |
| ) |
|
|
inlinestatic |
static const std::string world_model::FoundObjectHandler::GetPushFoundObjectServiceName |
( |
| ) |
|
|
inlinestatic |
static const std::string world_model::FoundObjectHandler::GetVisualizeSampledPosesName |
( |
| ) |
|
|
inlinestatic |
std::vector< geometry_msgs::Pose > world_model::FoundObjectHandler::interpolateOrientationAroundAxis |
( |
const geometry_msgs::Pose & |
poseToInterpolate, |
|
|
const double |
interpolationOffset, |
|
|
const Eigen::Vector3d & |
axisToRotate, |
|
|
const int |
numberOfInterpolationsPerOrientation |
|
) |
| const |
|
private |
bool world_model::FoundObjectHandler::processEmptyFoundObjectListServiceCall |
( |
std_srvs::Empty::Request & |
request, |
|
|
std_srvs::Empty::Response & |
response |
|
) |
| |
Empties the found object list.
- Parameters
-
request | the associated request object of the service call |
response | the associated response object of the service |
- Returns
- the success of the service call.
Definition at line 479 of file found_object_handler.cpp.
bool world_model::FoundObjectHandler::processGetFoundObjectListServiceCall |
( |
asr_world_model::GetFoundObjectList::Request & |
request, |
|
|
asr_world_model::GetFoundObjectList::Response & |
response |
|
) |
| |
Returns the already found objects.
- Parameters
-
request | the associated request object of the service call |
response | the associated response object of the service |
- Returns
- the success of the service call.
Definition at line 495 of file found_object_handler.cpp.
bool world_model::FoundObjectHandler::processPushFoundObjectListServiceCall |
( |
asr_world_model::PushFoundObjectList::Request & |
request, |
|
|
asr_world_model::PushFoundObjectList::Response & |
response |
|
) |
| |
Pushes the found object to a list.
- Parameters
-
request | the associated request object of the service call |
response | the associated response object of the service |
- Returns
- the success of the service call.
Definition at line 38 of file found_object_handler.cpp.
bool world_model::FoundObjectHandler::processPushFoundObjectServiceCall |
( |
asr_world_model::PushFoundObject::Request & |
request, |
|
|
asr_world_model::PushFoundObject::Response & |
response |
|
) |
| |
|
inline |
Pushes the found object to a list.
- Parameters
-
request | the associated request object of the service call |
response | the associated response object of the service |
- Returns
- the success of the service call.
Definition at line 147 of file found_object_handler.hpp.
bool world_model::FoundObjectHandler::processVisualizeSampledPosesCall |
( |
asr_world_model::VisualizeSampledPoses::Request & |
request, |
|
|
asr_world_model::VisualizeSampledPoses::Response & |
response |
|
) |
| |
bool world_model::FoundObjectHandler::pushFoundObject |
( |
asr_msgs::AsrObject & |
candidate | ) |
|
|
private |
- Parameters
-
candidate | the found object candidate |
- Returns
- the success of the action
Definition at line 51 of file found_object_handler.cpp.
geometry_msgs::Pose world_model::FoundObjectHandler::rotateOrientationAroundAxis |
( |
const geometry_msgs::Pose & |
poseToRotate, |
|
|
const double |
interpolationOffset, |
|
|
const Eigen::Vector3d & |
axisToRotate |
|
) |
| const |
|
private |
bool world_model::FoundObjectHandler::sampleFoundObject |
( |
asr_msgs::AsrObject & |
candidate | ) |
|
|
private |
Generates samples for object pose estimation to model uncertainty.
- Parameters
-
candidate | the found object candidate |
- Returns
- success of comunication with object database
Definition at line 193 of file found_object_handler.cpp.
bool world_model::FoundObjectHandler::transformToBaseFrame |
( |
asr_msgs::AsrObject & |
candidate | ) |
const |
|
private |
Transform object pose to base frame of world model.
- Parameters
-
candidate | the found object candidate |
Definition at line 167 of file found_object_handler.cpp.
void world_model::FoundObjectHandler::updateBestHypothesis |
( |
ModelObjectPtr & |
currentModelObjectPtr, |
|
|
const asr_msgs::AsrObject & |
candidate |
|
) |
| |
|
private |
void world_model::FoundObjectHandler::visualizeFoundObjects |
( |
| ) |
|
|
private |
const double world_model::FoundObjectHandler::DEG_TO_RAD = M_PI / 180.0 |
|
private |
const double world_model::FoundObjectHandler::EPSILON = 0.0001 |
|
private |
SettingsPtr world_model::FoundObjectHandler::settings_ptr_ |
|
private |
The documentation for this class was generated from the following files:
asr_world_model
Author(s): Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Trautmann Jeremias
autogenerated on Thu Jan 9 2020 07:20:01