Go to the documentation of this file.
42 #include <object_recognition_msgs/TableArray.h>
43 #include <moveit_msgs/CollisionObject.h>
44 #include <boost/thread/mutex.hpp>
54 namespace semantic_world
76 object_recognition_msgs::TableArray
getTablesInROI(
double minx,
double miny,
double minz,
double maxx,
double maxy,
82 std::vector<std::string>
getTableNamesInROI(
double minx,
double miny,
double minz,
double maxx,
double maxy,
90 std::vector<geometry_msgs::PoseStamped>
generatePlacePoses(
const std::string& table_name,
92 const geometry_msgs::Quaternion& object_orientation,
93 double resolution,
double delta_height = 0.01,
94 unsigned int num_heights = 2)
const;
101 std::vector<geometry_msgs::PoseStamped>
generatePlacePoses(
const object_recognition_msgs::Table& table,
103 const geometry_msgs::Quaternion& object_orientation,
104 double resolution,
double delta_height = 0.01,
105 unsigned int num_heights = 2)
const;
113 std::vector<geometry_msgs::PoseStamped>
generatePlacePoses(
const object_recognition_msgs::Table& table,
114 double resolution,
double height_above_table,
115 double delta_height = 0.01,
unsigned int num_heights = 2,
116 double min_distance_from_edge = 0.10)
const;
122 visualization_msgs::MarkerArray
getPlaceLocationsMarker(
const std::vector<geometry_msgs::PoseStamped>& poses)
const;
129 std::string
findObjectTable(
const geometry_msgs::Pose& pose,
double min_distance_from_edge = 0.0,
130 double min_vertical_offset = 0.0)
const;
132 bool isInsideTableContour(
const geometry_msgs::Pose& pose,
const object_recognition_msgs::Table& table,
133 double min_distance_from_edge = 0.0,
double min_vertical_offset = 0.0)
const;
140 void tableCallback(
const object_recognition_msgs::TableArrayPtr& msg);
bool isInsideTableContour(const geometry_msgs::Pose &pose, const object_recognition_msgs::Table &table, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
SemanticWorld(const planning_scene::PlanningSceneConstPtr &planning_scene)
A (simple) semantic world representation for pick and place and other tasks. Currently this is used o...
ros::Subscriber table_subscriber_
std::string findObjectTable(const geometry_msgs::Pose &pose, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
planning_scene::PlanningSceneConstPtr planning_scene_
ros::NodeHandle node_handle_
object_recognition_msgs::TableArray getTablesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
MOVEIT_CLASS_FORWARD(Shape)
shapes::Mesh * orientPlanarPolygon(const shapes::Mesh &polygon) const
void tableCallback(const object_recognition_msgs::TableArrayPtr &msg)
ros::Publisher planning_scene_diff_publisher_
boost::function< void()> TableCallbackFn
The signature for a callback on receiving table messages.
void transformTableArray(object_recognition_msgs::TableArray &table_array) const
void addTableCallback(const TableCallbackFn &table_callback)
std::vector< std::string > getTableNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
std::vector< geometry_msgs::PoseStamped > place_poses_
ros::Publisher collision_object_publisher_
std::vector< geometry_msgs::PoseStamped > generatePlacePoses(const std::string &table_name, const shapes::ShapeConstPtr &object_shape, const geometry_msgs::Quaternion &object_orientation, double resolution, double delta_height=0.01, unsigned int num_heights=2) const
Generate possible place poses on the table for a given object. This chooses appropriate values for mi...
MOVEIT_CLASS_FORWARD(SemanticWorld)
object_recognition_msgs::TableArray table_array_
visualization_msgs::MarkerArray getPlaceLocationsMarker(const std::vector< geometry_msgs::PoseStamped > &poses) const
bool addTablesToCollisionWorld()
ros::Publisher visualization_publisher_
A (simple) semantic world representation for pick and place and other tasks.
TableCallbackFn table_callback_
shapes::Mesh * createSolidMeshFromPlanarPolygon(const shapes::Mesh &polygon, double thickness) const
std::shared_ptr< const Shape > ShapeConstPtr
std::map< std::string, object_recognition_msgs::Table > current_tables_in_collision_world_
perception
Author(s): Ioan Sucan
, Jon Binney , Suat Gedikli
autogenerated on Wed Feb 21 2024 03:26:19