Class for processing objects recognized by ORK. More...
#include <objprocessing.hpp>
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 | |
MetaBlock * | getBlock (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< MetaBlock > | blocks_ |
moveit::planning_interface::PlanningSceneInterface | current_scene_ |
Evaluation * | evaluation_ |
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::NodeHandle * | nh_ |
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_ |
Class for processing objects recognized by ORK.
Definition at line 45 of file objprocessing.hpp.
moveit_simple_actions::ObjProcessor::ObjProcessor | ( | ros::NodeHandle * | nh, |
Evaluation * | evaluation | ||
) |
constructor
Definition at line 28 of file objprocessing.cpp.
void moveit_simple_actions::ObjProcessor::addBlock | ( | const MetaBlock & | block | ) |
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.
int moveit_simple_actions::ObjProcessor::getAmountOfBlocks | ( | ) | [inline] |
get amount of objects
Definition at line 59 of file objprocessing.hpp.
MetaBlock * moveit_simple_actions::ObjProcessor::getBlock | ( | const int & | id | ) |
get an object by id
Definition at line 243 of file objprocessing.cpp.
bool moveit_simple_actions::ObjProcessor::getMeshFromDB | ( | GetObjInfo & | obj_info | ) | [protected] |
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.
std::vector<MetaBlock> moveit_simple_actions::ObjProcessor::blocks_ [protected] |
set of available objects
Definition at line 120 of file objprocessing.hpp.
moveit::planning_interface::PlanningSceneInterface moveit_simple_actions::ObjProcessor::current_scene_ [protected] |
current MoveIt scene
Definition at line 117 of file objprocessing.hpp.
evaluation of reaching/grasping
Definition at line 87 of file objprocessing.hpp.
bool moveit_simple_actions::ObjProcessor::found_obj_reco_client_ [protected] |
if found object recognition server
Definition at line 108 of file objprocessing.hpp.
bool moveit_simple_actions::ObjProcessor::found_srv_obj_info_ [protected] |
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.
ros::NodeHandle* moveit_simple_actions::ObjProcessor::nh_ [protected] |
node handle
Definition at line 84 of file objprocessing.hpp.
boost::scoped_ptr<ObjRecoActionClient> moveit_simple_actions::ObjProcessor::obj_reco_client_ [protected] |
object recognition client
Definition at line 105 of file objprocessing.hpp.
const std::string moveit_simple_actions::ObjProcessor::OBJECT_RECOGNITION_ACTION [protected] |
object recognition action
Definition at line 90 of file objprocessing.hpp.
subscriber to object recognition topic
Definition at line 111 of file objprocessing.hpp.
std::string moveit_simple_actions::ObjProcessor::object_topic_ [protected] |
recognized object topic
Definition at line 96 of file objprocessing.hpp.
publisher of objects' poses
Definition at line 74 of file objprocessing.hpp.
std::string moveit_simple_actions::ObjProcessor::target_frame_ [protected] |
final object frame
Definition at line 93 of file objprocessing.hpp.