39 #include <rclcpp/rclcpp.hpp>
42 #include <object_recognition_msgs/msg/table_array.hpp>
43 #include <moveit_msgs/msg/collision_object.hpp>
53 namespace semantic_world
75 object_recognition_msgs::msg::TableArray
getTablesInROI(
double minx,
double miny,
double minz,
double maxx,
76 double maxy,
double maxz)
const;
81 std::vector<std::string>
getTableNamesInROI(
double minx,
double miny,
double minz,
double maxx,
double maxy,
89 std::vector<geometry_msgs::msg::PoseStamped>
90 generatePlacePoses(
const std::string& table_name,
const shapes::ShapeConstPtr& object_shape,
91 const geometry_msgs::msg::Quaternion& object_orientation,
double resolution,
92 double delta_height = 0.01,
unsigned int num_heights = 2)
const;
99 std::vector<geometry_msgs::msg::PoseStamped>
100 generatePlacePoses(
const object_recognition_msgs::msg::Table& table,
const shapes::ShapeConstPtr& object_shape,
101 const geometry_msgs::msg::Quaternion& object_orientation,
double resolution,
102 double delta_height = 0.01,
unsigned int num_heights = 2)
const;
110 std::vector<geometry_msgs::msg::PoseStamped>
generatePlacePoses(
const object_recognition_msgs::msg::Table& table,
111 double resolution,
double height_above_table,
112 double delta_height = 0.01,
113 unsigned int num_heights = 2,
114 double min_distance_from_edge = 0.10)
const;
120 visualization_msgs::msg::MarkerArray
125 table_callback_ = table_callback;
128 std::string
findObjectTable(
const geometry_msgs::msg::Pose& pose,
double min_distance_from_edge = 0.0,
129 double min_vertical_offset = 0.0)
const;
131 bool isInsideTableContour(
const geometry_msgs::msg::Pose& pose,
const object_recognition_msgs::msg::Table& table,
132 double min_distance_from_edge = 0.0,
double min_vertical_offset = 0.0)
const;
135 shapes::Mesh* createSolidMeshFromPlanarPolygon(
const shapes::Mesh& polygon,
double thickness)
const;
137 shapes::Mesh* orientPlanarPolygon(
const shapes::Mesh& polygon)
const;
139 void tableCallback(
const object_recognition_msgs::msg::TableArray::ConstSharedPtr& msg);
141 void transformTableArray(object_recognition_msgs::msg::TableArray& table_array)
const;
143 planning_scene::PlanningSceneConstPtr planning_scene_;
145 rclcpp::Node::SharedPtr node_handle_;
147 object_recognition_msgs::msg::TableArray table_array_;
149 std::vector<geometry_msgs::msg::PoseStamped> place_poses_;
151 std::map<std::string, object_recognition_msgs::msg::Table> current_tables_in_collision_world_;
153 rclcpp::Subscription<object_recognition_msgs::msg::TableArray>::SharedPtr table_subscriber_;
155 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr visualization_publisher_;
156 rclcpp::Publisher<moveit_msgs::msg::CollisionObject>::SharedPtr collision_object_publisher_;
160 rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_diff_publisher_;
A (simple) semantic world representation for pick and place and other tasks.
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.
bool addTablesToCollisionWorld()
object_recognition_msgs::msg::TableArray getTablesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz) const
Get all the tables within a region of interest.
visualization_msgs::msg::MarkerArray getPlaceLocationsMarker(const std::vector< geometry_msgs::msg::PoseStamped > &poses) const
std::string findObjectTable(const geometry_msgs::msg::Pose &pose, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
std::vector< geometry_msgs::msg::PoseStamped > generatePlacePoses(const std::string &table_name, const shapes::ShapeConstPtr &object_shape, const geometry_msgs::msg::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...
bool isInsideTableContour(const geometry_msgs::msg::Pose &pose, const object_recognition_msgs::msg::Table &table, double min_distance_from_edge=0.0, double min_vertical_offset=0.0) const
void addTableCallback(const TableCallbackFn &table_callback)
std::function< void()> TableCallbackFn
The signature for a callback on receiving table messages.
SemanticWorld(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningSceneConstPtr &planning_scene)
A (simple) semantic world representation for pick and place and other tasks. Currently this is used o...
MOVEIT_CLASS_FORWARD(SemanticWorld)
Main namespace for MoveIt.
This namespace includes the central class for representing planning contexts.
MOVEIT_CLASS_FORWARD(Shape)