objprocessing.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 SoftBank Robotics Europe
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015 */
00016 
00017 #ifndef OBJPROCESSING_HPP
00018 #define OBJPROCESSING_HPP
00019 
00020 #include <boost/scoped_ptr.hpp>
00021 
00022 // ROS
00023 #include <ros/ros.h>
00024 
00025 #include <tf/transform_listener.h>
00026 
00027 #include <geometry_msgs/PoseArray.h>
00028 
00029 #include <actionlib/client/simple_action_client.h>
00030 
00031 #include <object_recognition_msgs/GetObjectInformation.h>
00032 #include <object_recognition_msgs/ObjectRecognitionAction.h>
00033 
00034 #include "romeo_moveit_actions/metablock.hpp"
00035 #include "romeo_moveit_actions/evaluation.hpp"
00036 
00037 typedef object_recognition_msgs::RecognizedObjectArray RecognizedObjArray;
00038 typedef actionlib::SimpleActionClient<object_recognition_msgs::ObjectRecognitionAction> ObjRecoActionClient;
00039 typedef object_recognition_msgs::GetObjectInformation GetObjInfo;
00040 
00041 namespace moveit_simple_actions
00042 {
00043 
00045 class ObjProcessor
00046 {
00047 public:
00049   ObjProcessor(ros::NodeHandle *nh,
00050                Evaluation *evaluation);
00051 
00053   bool triggerObjectDetection();
00054 
00056   void getRecognizedObjects(const RecognizedObjArray::ConstPtr& msg);
00057 
00059   int getAmountOfBlocks()
00060   {
00061     return blocks_.size();
00062   }
00063 
00065   MetaBlock * getBlock(const int &id);
00066 
00068   void addBlock(const MetaBlock &block);
00069 
00071   void cleanObjects(const bool list_erase=true);
00072 
00074   ros::Publisher pub_obj_poses_;
00075 
00076 protected:
00078   bool getMeshFromDB(GetObjInfo &obj_info);
00079 
00081   void publishAllCollObj(std::vector<MetaBlock> *blocks);
00082 
00084   ros::NodeHandle *nh_;
00085 
00087   Evaluation *evaluation_;
00088 
00090   const std::string OBJECT_RECOGNITION_ACTION;
00091 
00093   std::string target_frame_;
00094 
00096   std::string object_topic_;
00097 
00099   bool found_srv_obj_info_;
00100 
00102   ros::ServiceClient get_model_mesh_srv_;
00103 
00105   boost::scoped_ptr<ObjRecoActionClient> obj_reco_client_;
00106 
00108   bool found_obj_reco_client_;
00109 
00111   ros::Subscriber object_sub_;
00112 
00114   tf::TransformListener listener_;
00115 
00117   moveit::planning_interface::PlanningSceneInterface current_scene_;
00118 
00120   std::vector<MetaBlock> blocks_;
00121 
00123   geometry_msgs::PoseArray msg_obj_poses_;
00124 };
00125 }
00126 #endif // OBJPROCESSING_HPP


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