Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
moveit_simple_actions::ObjProcessor Class Reference

Class for processing objects recognized by ORK. More...

#include <objprocessing.hpp>

List of all members.

Public Member Functions

void addBlock (const MetaBlock &block)
 add a new object to the end
void cleanObjects (const bool list_erase=true)
 clean the list of objects based on the timestamp
int getAmountOfBlocks ()
 get amount of objects
MetaBlockgetBlock (const int &id)
 get an object by id
void getRecognizedObjects (const RecognizedObjArray::ConstPtr &msg)
 convert object recognition messages into collision objects
 ObjProcessor (ros::NodeHandle *nh, Evaluation *evaluation)
 constructor
bool triggerObjectDetection ()
 trigger object detection client

Public Attributes

ros::Publisher pub_obj_poses_

Protected Member Functions

bool getMeshFromDB (GetObjInfo &obj_info)
 get the object's mesh from the DB
void publishAllCollObj (std::vector< MetaBlock > *blocks)
 publish all collision objects in MoveIt

Protected Attributes

std::vector< MetaBlockblocks_
moveit::planning_interface::PlanningSceneInterface current_scene_
Evaluationevaluation_
bool found_obj_reco_client_
bool found_srv_obj_info_
ros::ServiceClient get_model_mesh_srv_
tf::TransformListener listener_
geometry_msgs::PoseArray msg_obj_poses_
 all objects positions
ros::NodeHandlenh_
boost::scoped_ptr
< ObjRecoActionClient
obj_reco_client_
const std::string OBJECT_RECOGNITION_ACTION
ros::Subscriber object_sub_
std::string object_topic_
std::string target_frame_

Detailed Description

Class for processing objects recognized by ORK.

Definition at line 45 of file objprocessing.hpp.


Constructor & Destructor Documentation

constructor

Definition at line 28 of file objprocessing.cpp.


Member Function Documentation

add a new object to the end

Definition at line 251 of file objprocessing.cpp.

void moveit_simple_actions::ObjProcessor::cleanObjects ( const bool  list_erase = true)

clean the list of objects based on the timestamp

Definition at line 259 of file objprocessing.cpp.

get amount of objects

Definition at line 59 of file objprocessing.hpp.

get an object by id

Definition at line 243 of file objprocessing.cpp.

get the object's mesh from the DB

Definition at line 114 of file objprocessing.cpp.

void moveit_simple_actions::ObjProcessor::getRecognizedObjects ( const RecognizedObjArray::ConstPtr &  msg)

convert object recognition messages into collision objects

Definition at line 127 of file objprocessing.cpp.

void moveit_simple_actions::ObjProcessor::publishAllCollObj ( std::vector< MetaBlock > *  blocks) [protected]

publish all collision objects in MoveIt

Definition at line 228 of file objprocessing.cpp.

trigger object detection client

Definition at line 68 of file objprocessing.cpp.


Member Data Documentation

set of available objects

Definition at line 120 of file objprocessing.hpp.

current MoveIt scene

Definition at line 117 of file objprocessing.hpp.

evaluation of reaching/grasping

Definition at line 87 of file objprocessing.hpp.

if found object recognition server

Definition at line 108 of file objprocessing.hpp.

if found object info server

Definition at line 99 of file objprocessing.hpp.

Client for getting the mesh for a database object

Definition at line 102 of file objprocessing.hpp.

transform listener

Definition at line 114 of file objprocessing.hpp.

geometry_msgs::PoseArray moveit_simple_actions::ObjProcessor::msg_obj_poses_ [protected]

all objects positions

Definition at line 123 of file objprocessing.hpp.

node handle

Definition at line 84 of file objprocessing.hpp.

object recognition client

Definition at line 105 of file objprocessing.hpp.

object recognition action

Definition at line 90 of file objprocessing.hpp.

subscriber to object recognition topic

Definition at line 111 of file objprocessing.hpp.

recognized object topic

Definition at line 96 of file objprocessing.hpp.

publisher of objects' poses

Definition at line 74 of file objprocessing.hpp.

final object frame

Definition at line 93 of file objprocessing.hpp.


The documentation for this class was generated from the following files:


romeo_moveit_actions
Author(s):
autogenerated on Thu Jun 6 2019 21:57:24