Skip to content

Commit

Permalink
and, now that the debs are correct, using sensor_msgs.point_cloud2 ra…
Browse files Browse the repository at this point in the history
…ther tahn my local copy of it
  • Loading branch information
lindzey committed Dec 12, 2013
1 parent 342fcd2 commit 2454df7
Show file tree
Hide file tree
Showing 4 changed files with 3 additions and 148 deletions.
2 changes: 1 addition & 1 deletion clear_table/scripts/run_segmentation.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

import actionlib
from cv_bridge import CvBridge
import clear_table.handle_point_cloud2 as pts
import sensor_msgs.point_cloud2 as pts

from sensor_msgs.msg import Image, CameraInfo, PointCloud2
from shared_autonomy_msgs.msg import SegmentGoal, SegmentAction
Expand Down
144 changes: 0 additions & 144 deletions clear_table/src/clear_table/handle_point_cloud2.py

This file was deleted.

2 changes: 1 addition & 1 deletion clear_table/src/clear_table/scene_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import rospy
import tf

import clear_table.handle_point_cloud2 as pts
import sensor_msgs.point_cloud2 as pts

from geometry_msgs.msg import Point, PoseStamped, Vector3
from moveit_msgs.msg import AttachedCollisionObject, CollisionObject, PlanningSceneWorld
Expand Down
3 changes: 1 addition & 2 deletions clear_table/src/clear_table/sensor_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

import actionlib
from cv_bridge import CvBridge
import clear_table.handle_point_cloud2 as pts
import sensor_msgs.point_cloud2 as pts

from sensor_msgs.msg import PointCloud2
from shared_autonomy_msgs.msg import SegmentGoal, SegmentAction
Expand Down Expand Up @@ -68,7 +68,6 @@ def get_point_cloud(self, data, mask):
print e
return []

# TODO: depend on the read_points that should be in common_msgs?
# TODO: why didn't the uvs=idxs code work? x
pt_gen = pts.read_points(data.points)#, uvs=idxs, skip_nans=True) # this didn't work!!

Expand Down

0 comments on commit 2454df7

Please sign in to comment.