51 catch (
const std::exception& ex)
53 ROS_FATAL(
"Exception during destruction of Visualization: %s", ex.what());
57 ROS_FATAL(
"Exception during destruction of Visualization");
62 const rc_pick_client::LoadCarrier& lc,
const int& lc_no)
64 visualization_msgs::Marker marker;
65 marker.header.frame_id = lc.pose.header.frame_id;
66 marker.type = marker.CUBE;
67 marker.color.r = 0.0f;
68 marker.color.g = 0.20f;
69 marker.color.b = 0.80f;
72 lc.pose.pose.orientation.z, lc.pose.pose.orientation.w),
73 tf2::Vector3(lc.pose.pose.position.x, lc.pose.pose.position.y, lc.pose.pose.position.z));
75 double rim_thickness_x = (lc.outer_dimensions.x - lc.inner_dimensions.x) / 2;
76 double dist_from_center_x = (lc.outer_dimensions.x - rim_thickness_x) / 2;
77 double rim_thickness_y = (lc.outer_dimensions.y - lc.inner_dimensions.y) / 2;
78 double dist_from_center_y = (lc.outer_dimensions.y - rim_thickness_y) / 2;
79 double bottom_thickness = lc.outer_dimensions.z - lc.inner_dimensions.z;
80 tf2::Vector3 pose(0, 0, -(lc.outer_dimensions.z - bottom_thickness) / 2);
83 pose = bin_transform * pose;
85 marker.pose = lc.pose.pose;
86 marker.pose.position.x = pose.getX();
87 marker.pose.position.y = pose.getY();
88 marker.pose.position.z = pose.getZ();
89 marker.scale.x = lc.outer_dimensions.x;
90 marker.scale.y = lc.outer_dimensions.y;
91 marker.scale.z = bottom_thickness;
92 marker_array.markers.push_back(marker);
95 pose = tf2::Vector3(dist_from_center_x, 0, 0);
96 pose = bin_transform * pose;
98 marker.id = lc_no + 1;
99 marker.pose = lc.pose.pose;
100 marker.pose.position.x = pose.getX();
101 marker.pose.position.y = pose.getY();
102 marker.pose.position.z = pose.getZ();
103 marker.scale.x = rim_thickness_x;
104 marker.scale.y = lc.outer_dimensions.y;
105 marker.scale.z = lc.outer_dimensions.z;
106 marker_array.markers.push_back(marker);
108 marker.id = lc_no + 2;
109 pose = tf2::Vector3(-dist_from_center_x, 0, 0);
110 pose = bin_transform * pose;
111 marker.pose.position.x = pose.getX();
112 marker.pose.position.y = pose.getY();
113 marker.pose.position.z = pose.getZ();
114 marker_array.markers.push_back(marker);
117 marker.id = lc_no + 3;
118 pose = tf2::Vector3(0, dist_from_center_y, 0);
119 pose = bin_transform * pose;
120 marker.pose = lc.pose.pose;
121 marker.pose.position.x = pose.getX();
122 marker.pose.position.y = pose.getY();
123 marker.pose.position.z = pose.getZ();
124 marker.scale.x = lc.outer_dimensions.x;
125 marker.scale.y = rim_thickness_y;
126 marker.scale.z = lc.outer_dimensions.z;
127 marker_array.markers.push_back(marker);
129 marker.id = lc_no + 4;
130 pose = tf2::Vector3(0, -dist_from_center_y, 0);
131 pose = bin_transform * pose;
132 marker.pose = lc.pose.pose;
133 marker.pose.position.x = pose.getX();
134 marker.pose.position.y = pose.getY();
135 marker.pose.position.z = pose.getZ();
136 marker.scale.x = lc.outer_dimensions.x;
137 marker_array.markers.push_back(marker);
144 i.action = visualization_msgs::Marker::DELETE;
154 i.action = visualization_msgs::Marker::DELETE;
164 i.action = visualization_msgs::Marker::DELETE;
173 if (!ros_lcs.empty())
176 for (
auto& single_lc : ros_lcs)
179 publishTf(single_lc.pose.pose, single_lc.pose.header.frame_id,
"lc_" + std::to_string(counter));
189 if (!ros_grasps.empty())
192 visualization_msgs::Marker marker;
193 marker.action = visualization_msgs::Marker::ADD;
194 marker.type = marker.SPHERE;
195 rc_pick_client::Rectangle rect;
196 for (
auto& single_grasp : ros_grasps)
198 rect.x = single_grasp.max_suction_surface_length;
199 rect.y = single_grasp.max_suction_surface_width;
200 setMarker(marker, single_grasp.pose.pose, rect, single_grasp.pose.header.frame_id, counter);
201 publishTf(single_grasp.pose.pose, single_grasp.pose.header.frame_id,
"grasp_" + std::to_string(counter));
212 if (!ros_boxitems.empty())
215 visualization_msgs::Marker marker;
216 marker.type = marker.CUBE;
217 for (
auto& item : ros_boxitems)
219 setMarker(marker, item.pose.pose, item.rectangle, item.pose.header.frame_id, counter);
220 publishTf(item.pose.pose, item.pose.header.frame_id,
"boxitem_" + std::to_string(counter));
229 const rc_pick_client::Rectangle& rectangle, std::string frame_id,
int marker_id)
231 marker.scale.z = 0.001;
232 marker.color.r = 0.800f;
233 marker.color.g = 0.20f;
234 marker.color.b = 0.0f;
235 marker.color.a = 0.80;
236 marker.action = visualization_msgs::Marker::ADD;
237 marker.id = marker_id;
238 marker.header.frame_id = frame_id;
239 marker.pose = item_pose;
240 marker.scale.x = rectangle.x;
241 marker.scale.y = rectangle.y;
247 transform.
setOrigin(tf::Vector3(ros_pose.position.x, ros_pose.position.y, ros_pose.position.z));
249 tf::Quaternion(ros_pose.orientation.x, ros_pose.orientation.y, ros_pose.orientation.z, ros_pose.orientation.w));