Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
turtlebot_arm_object_manipulation::ObjectDetectionServer Class Reference

Classes

class  DetectionBin
 
struct  TableDescriptor
 

Public Member Functions

void goalCB ()
 
 ObjectDetectionServer (const std::string name)
 
void preemptCB ()
 
void tableCb (const object_recognition_msgs::TableArray &msg)
 

Private Member Functions

int addObjects (const std::vector< DetectionBin > &detection_bins)
 
void addTable (const std::vector< geometry_msgs::Pose > &table_poses, const std::vector< TableDescriptor > &table_params)
 
const object_recognition_msgs::ObjectInformation & getObjInfo (const object_recognition_msgs::ObjectType &obj_type)
 
std_msgs::ColorRGBA getRandColor (float alpha=1.0)
 
TableDescriptor getTableParams (std::vector< geometry_msgs::Point > convex_hull)
 
double median (std::vector< double > &values)
 
bool transformPose (const std::string &in_frame, const std::string &out_frame, const geometry_msgs::Pose &in_pose, geometry_msgs::Pose &out_pose)
 

Private Attributes

std::string action_name_
 
std::string arm_link_
 
const unsigned CALLS_TO_ORK_TABLETOP = 10
 
ros::Publisher clear_objs_pub_
 
ros::Publisher clear_table_pub_
 
const double CLUSTERING_THRESHOLD = 0.05
 
const double CONFIDENCE_THRESHOLD = 0.85
 
turtlebot_arm_object_manipulation::ObjectDetectionFeedback feedback_
 
turtlebot_arm_object_manipulation::ObjectDetectionGoalConstPtr goal_
 
ros::NodeHandle nh_
 
ros::ServiceClient obj_info_srv_
 
std::map< std::string, object_recognition_msgs::ObjectInformation > objs_info_
 
actionlib::SimpleActionServer< turtlebot_arm_object_manipulation::ObjectDetectionAction > od_as_
 
actionlib::SimpleActionClient< object_recognition_msgs::ObjectRecognitionAction > ork_ac_
 
ros::Duration ork_execute_timeout_
 
ros::Duration ork_preempt_timeout_
 
moveit::planning_interface::PlanningSceneInterface planning_scene_interface_
 
ros::NodeHandle pnh_
 
turtlebot_arm_object_manipulation::ObjectDetectionResult result_
 
std::vector< TableDescriptortable_params_
 
std::vector< geometry_msgs::Posetable_poses_
 
ros::Subscriber table_sub_
 
tf::TransformListener tf_listener_
 

Detailed Description

Definition at line 63 of file object_detection_action_server.cpp.

Constructor & Destructor Documentation

turtlebot_arm_object_manipulation::ObjectDetectionServer::ObjectDetectionServer ( const std::string  name)
inline

Definition at line 121 of file object_detection_action_server.cpp.

Member Function Documentation

int turtlebot_arm_object_manipulation::ObjectDetectionServer::addObjects ( const std::vector< DetectionBin > &  detection_bins)
inlineprivate

Definition at line 323 of file object_detection_action_server.cpp.

void turtlebot_arm_object_manipulation::ObjectDetectionServer::addTable ( const std::vector< geometry_msgs::Pose > &  table_poses,
const std::vector< TableDescriptor > &  table_params 
)
inlineprivate

Definition at line 406 of file object_detection_action_server.cpp.

const object_recognition_msgs::ObjectInformation& turtlebot_arm_object_manipulation::ObjectDetectionServer::getObjInfo ( const object_recognition_msgs::ObjectType &  obj_type)
inlineprivate

Definition at line 571 of file object_detection_action_server.cpp.

std_msgs::ColorRGBA turtlebot_arm_object_manipulation::ObjectDetectionServer::getRandColor ( float  alpha = 1.0)
inlineprivate

Definition at line 594 of file object_detection_action_server.cpp.

TableDescriptor turtlebot_arm_object_manipulation::ObjectDetectionServer::getTableParams ( std::vector< geometry_msgs::Point convex_hull)
inlineprivate

Definition at line 470 of file object_detection_action_server.cpp.

void turtlebot_arm_object_manipulation::ObjectDetectionServer::goalCB ( )
inline

Definition at line 163 of file object_detection_action_server.cpp.

double turtlebot_arm_object_manipulation::ObjectDetectionServer::median ( std::vector< double > &  values)
inlineprivate

Definition at line 525 of file object_detection_action_server.cpp.

void turtlebot_arm_object_manipulation::ObjectDetectionServer::preemptCB ( )
inline

Definition at line 271 of file object_detection_action_server.cpp.

void turtlebot_arm_object_manipulation::ObjectDetectionServer::tableCb ( const object_recognition_msgs::TableArray &  msg)
inline

Definition at line 278 of file object_detection_action_server.cpp.

bool turtlebot_arm_object_manipulation::ObjectDetectionServer::transformPose ( const std::string &  in_frame,
const std::string &  out_frame,
const geometry_msgs::Pose in_pose,
geometry_msgs::Pose out_pose 
)
inlineprivate

Definition at line 534 of file object_detection_action_server.cpp.

Member Data Documentation

std::string turtlebot_arm_object_manipulation::ObjectDetectionServer::action_name_
private

Definition at line 83 of file object_detection_action_server.cpp.

std::string turtlebot_arm_object_manipulation::ObjectDetectionServer::arm_link_
private

Definition at line 113 of file object_detection_action_server.cpp.

const unsigned turtlebot_arm_object_manipulation::ObjectDetectionServer::CALLS_TO_ORK_TABLETOP = 10
private

Definition at line 118 of file object_detection_action_server.cpp.

ros::Publisher turtlebot_arm_object_manipulation::ObjectDetectionServer::clear_objs_pub_
private

Definition at line 92 of file object_detection_action_server.cpp.

ros::Publisher turtlebot_arm_object_manipulation::ObjectDetectionServer::clear_table_pub_
private

Definition at line 93 of file object_detection_action_server.cpp.

const double turtlebot_arm_object_manipulation::ObjectDetectionServer::CLUSTERING_THRESHOLD = 0.05
private

Definition at line 117 of file object_detection_action_server.cpp.

const double turtlebot_arm_object_manipulation::ObjectDetectionServer::CONFIDENCE_THRESHOLD = 0.85
private

Definition at line 116 of file object_detection_action_server.cpp.

turtlebot_arm_object_manipulation::ObjectDetectionFeedback turtlebot_arm_object_manipulation::ObjectDetectionServer::feedback_
private

Definition at line 80 of file object_detection_action_server.cpp.

turtlebot_arm_object_manipulation::ObjectDetectionGoalConstPtr turtlebot_arm_object_manipulation::ObjectDetectionServer::goal_
private

Definition at line 82 of file object_detection_action_server.cpp.

ros::NodeHandle turtlebot_arm_object_manipulation::ObjectDetectionServer::nh_
private

Definition at line 65 of file object_detection_action_server.cpp.

ros::ServiceClient turtlebot_arm_object_manipulation::ObjectDetectionServer::obj_info_srv_
private

Definition at line 86 of file object_detection_action_server.cpp.

std::map<std::string, object_recognition_msgs::ObjectInformation> turtlebot_arm_object_manipulation::ObjectDetectionServer::objs_info_
private

Definition at line 87 of file object_detection_action_server.cpp.

actionlib::SimpleActionServer<turtlebot_arm_object_manipulation::ObjectDetectionAction> turtlebot_arm_object_manipulation::ObjectDetectionServer::od_as_
private

Definition at line 79 of file object_detection_action_server.cpp.

actionlib::SimpleActionClient<object_recognition_msgs::ObjectRecognitionAction> turtlebot_arm_object_manipulation::ObjectDetectionServer::ork_ac_
private

Definition at line 74 of file object_detection_action_server.cpp.

ros::Duration turtlebot_arm_object_manipulation::ObjectDetectionServer::ork_execute_timeout_
private

Definition at line 75 of file object_detection_action_server.cpp.

ros::Duration turtlebot_arm_object_manipulation::ObjectDetectionServer::ork_preempt_timeout_
private

Definition at line 76 of file object_detection_action_server.cpp.

moveit::planning_interface::PlanningSceneInterface turtlebot_arm_object_manipulation::ObjectDetectionServer::planning_scene_interface_
private

Definition at line 108 of file object_detection_action_server.cpp.

ros::NodeHandle turtlebot_arm_object_manipulation::ObjectDetectionServer::pnh_
private

Definition at line 71 of file object_detection_action_server.cpp.

turtlebot_arm_object_manipulation::ObjectDetectionResult turtlebot_arm_object_manipulation::ObjectDetectionServer::result_
private

Definition at line 81 of file object_detection_action_server.cpp.

std::vector<TableDescriptor> turtlebot_arm_object_manipulation::ObjectDetectionServer::table_params_
private

Definition at line 105 of file object_detection_action_server.cpp.

std::vector<geometry_msgs::Pose> turtlebot_arm_object_manipulation::ObjectDetectionServer::table_poses_
private

Definition at line 104 of file object_detection_action_server.cpp.

ros::Subscriber turtlebot_arm_object_manipulation::ObjectDetectionServer::table_sub_
private

Definition at line 90 of file object_detection_action_server.cpp.

tf::TransformListener turtlebot_arm_object_manipulation::ObjectDetectionServer::tf_listener_
private

Definition at line 110 of file object_detection_action_server.cpp.


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


turtlebot_arm_object_manipulation
Author(s): Jorge Santos
autogenerated on Fri Feb 7 2020 03:56:40