Public Member Functions | |
| Eigen::Vector4f | getMovedCentroid () |
| Eigen::Vector4f | getMovedPoint (geometry_msgs::Point p) |
| PushVector | getPushVector () |
| PushOpt (ProtoObject &_obj, double _push_angle, Eigen::Vector3f _push_vec, unsigned int _obj_idx, unsigned int _split_id, double _push_dist, double _split_score, int bin) | |
| XYZPointCloud | pushPointCloud (XYZPointCloud &cloud_in) |
Static Public Member Functions | |
| static bool | compareOpts (PushOpt a, PushOpt b) |
Public Attributes | |
| bool | bad_angle |
| unsigned int | boundary_idx |
| bool | next_bin_filled |
| ProtoObject | obj |
| unsigned int | object_idx |
| bool | prev_bin_filled |
| double | push_angle |
| unsigned int | push_bin |
| double | push_dist |
| Eigen::Vector3f | push_unit_vec |
| unsigned int | split_id |
| double | split_score |
| bool | start_collides |
| bool | start_leaves |
| geometry_msgs::Point | start_point |
| bool | will_collide |
| bool | will_leave |
| bool | will_leave_table |
Definition at line 139 of file object_singulation_node.cpp.
| PushOpt::PushOpt | ( | ProtoObject & | _obj, |
| double | _push_angle, | ||
| Eigen::Vector3f | _push_vec, | ||
| unsigned int | _obj_idx, | ||
| unsigned int | _split_id, | ||
| double | _push_dist, | ||
| double | _split_score, | ||
| int | bin | ||
| ) | [inline] |
Definition at line 141 of file object_singulation_node.cpp.
| static bool PushOpt::compareOpts | ( | PushOpt | a, |
| PushOpt | b | ||
| ) | [inline, static] |
Return true if a is a better option than b
| a | first option |
| b | second option |
Definition at line 210 of file object_singulation_node.cpp.
| Eigen::Vector4f PushOpt::getMovedCentroid | ( | ) | [inline] |
Definition at line 164 of file object_singulation_node.cpp.
| Eigen::Vector4f PushOpt::getMovedPoint | ( | geometry_msgs::Point | p | ) | [inline] |
Definition at line 154 of file object_singulation_node.cpp.
| PushVector PushOpt::getPushVector | ( | ) | [inline] |
Definition at line 174 of file object_singulation_node.cpp.
| XYZPointCloud PushOpt::pushPointCloud | ( | XYZPointCloud & | cloud_in | ) | [inline] |
Definition at line 186 of file object_singulation_node.cpp.
Definition at line 282 of file object_singulation_node.cpp.
| unsigned int PushOpt::boundary_idx |
Definition at line 288 of file object_singulation_node.cpp.
Definition at line 284 of file object_singulation_node.cpp.
Definition at line 271 of file object_singulation_node.cpp.
| unsigned int PushOpt::object_idx |
Definition at line 274 of file object_singulation_node.cpp.
Definition at line 283 of file object_singulation_node.cpp.
| double PushOpt::push_angle |
Definition at line 272 of file object_singulation_node.cpp.
| unsigned int PushOpt::push_bin |
Definition at line 287 of file object_singulation_node.cpp.
| double PushOpt::push_dist |
Definition at line 276 of file object_singulation_node.cpp.
| Eigen::Vector3f PushOpt::push_unit_vec |
Definition at line 273 of file object_singulation_node.cpp.
| unsigned int PushOpt::split_id |
Definition at line 275 of file object_singulation_node.cpp.
| double PushOpt::split_score |
Definition at line 286 of file object_singulation_node.cpp.
Definition at line 280 of file object_singulation_node.cpp.
Definition at line 281 of file object_singulation_node.cpp.
Definition at line 285 of file object_singulation_node.cpp.
Definition at line 277 of file object_singulation_node.cpp.
Definition at line 278 of file object_singulation_node.cpp.
Definition at line 279 of file object_singulation_node.cpp.