Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[roseus_tutorials] add tf bbox sample #703

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion roseus_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ catkin_package(
# LIBRARIES # TODO
)

install(DIRECTORY launch src img config
install(DIRECTORY launch src sample img config
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS)

Expand Down
8 changes: 8 additions & 0 deletions roseus_tutorials/sample/euslisp/pr2-setting.l
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#!/usr/bin/env roseus
(require :pr2-interface "package://pr2eus/pr2-interface.l")
(setq *input-bbox-array* (ros::get-param "~/input_bbox_array" "/HSI_color_filter/boxes"))
(setq *base-frame-id* (ros::get-param "~base_frame_id" "/base_footprint"))
(setq *camera-frame-id* (ros::get-param "~camera_frame_id" ":head_mount_kinect_rgb_optical_frame_lk"))
(pr2-init)
(setq *robot* *pr2*)
(load "package://roseus_tutorials/src/display-tf-bounding-box-array.l")
160 changes: 160 additions & 0 deletions roseus_tutorials/sample/rviz/hsi_color_filter.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,160 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 728
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: PointCloud2
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: RGB8
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Min Color: 0; 0; 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /kinect_head/depth_registered/points
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: jsk_rviz_plugin/BoundingBoxArray
Enabled: true
Name: BoundingBoxArray
Topic: /HSI_color_filter/boxes
Unreliable: false
Value: true
alpha: 0.800000011920929
color: 25; 255; 0
coloring: Auto
line width: 0.004999999888241291
only edge: false
show coords: false
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base_footprint
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 1.8979061841964722
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.4162523150444031
Y: 0.027002409100532532
Z: 0.7402926087379456
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.4403988718986511
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 3.178584575653076
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1025
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000015600000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004cc0000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1853
X: 67
Y: 27
36 changes: 36 additions & 0 deletions roseus_tutorials/sample/sample_hsi_color_filter.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
<launch>
<arg name="gui" default="true"/>
<arg name="play_rosbag" default="true"/>
<arg name="input" default="/kinect_head/depth_registered/points"/>
<arg name="base_frame_id" default="base_footprint"/>
<arg name="input_bbox_array" default="/HSI_color_filter/boxes"/>
<arg name="camera_frame_id" default=":head_mount_kinect_rgb_optical_frame_lk"/>

<include if="$(arg play_rosbag)"
file="$(find jsk_pcl_ros)/sample/include/play_rosbag_pr2_sink.xml"/>

<!-- filter red color -->
<include file="$(find roseus_tutorials)/launch/hsi_color_filter.launch">
<arg name="INPUT" value="$(arg input)"/>
<arg name="h_max" value="50" />
<arg name="h_min" value="-20" />
<arg name="s_max" value="255" />
<arg name="s_min" value="120" />
<arg name="i_max" value="255" />
<arg name="i_min" value="70" />
</include>

<node name="pr2_display_tf_bbox_array" pkg="roseus_tutorials" type="pr2-setting.l" output="screen">
<rosparam subst_value="true">
base_frame_id: $(arg base_frame_id)
input_bbox_array: $(arg input_bbox_array)
camera_frame_id: $(arg camera_frame_id)
</rosparam>
</node>

<group if="$(arg gui)">
<node name="rviz"
pkg="rviz" type="rviz"
args="-d $(find roseus_tutorials)/sample/rviz/hsi_color_filter.rviz"/>
</group>
</launch>
48 changes: 48 additions & 0 deletions roseus_tutorials/src/display-tf-bounding-box-array.l
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
#!/usr/bin/env roseus

(ros::load-ros-manifest "jsk_recognition_msgs")

(setq *input-bbox-array* (ros::get-param "~/input_bbox_array" "/HSI_color_filter/boxes"))
(setq *base-frame-id* (ros::get-param "~base_frame_id" "/base_footprint"))
(setq *camera-frame-id* (ros::get-param "~camera_frame_id" ":head_mount_kinect_rgb_optical_frame_lk"))
;;(setq *robot* (ros::get-param "~robot" *pr2*))

(defun bounding-box-array-cb (msg)
(unless (send msg :boxes)
(return-from bounding-box-array-cb))
(let ((bounding-box-list (send msg :boxes)))
(when bounding-box-list
(send *robot* :angle-vector (send *ri* :potentio-vector))
(send *tfl* :wait-for-transform *base-frame-id* (send msg :header :frame_id) (ros::time 0) 10)
(mapcar
#'(lambda (b)
(let* ((dims (ros::tf-point->pos (send b :dimensions)))
(bx (make-cube (elt dims 0) (elt dims 1) (elt dims 2)))
;; Convert geoometry_msgs::Pose of BoundingBox to euslisp coordinates [mm]
(cam->obj-coords (ros::tf-pose->coords (send b :pose)))
;; Get camera coordinates [mm]
(base->cam-coords (send *tfl* :lookup-transform
*base-frame-id* (send b :header :frame_id)
(ros::time 0))))
;;(base->cam-coords (send (send *robot* *camera-frame-id*) :copy-worldcoords)))
;; Get BoundingBox world coordinates [mm]
(send bx :transform
(send (send base->cam-coords :copy-worldcoords)
:transform cam->obj-coords))
(objects (list bx base->cam-coords *robot*))
bx))
bounding-box-list)
)))

(ros::roseus "display-tf-bounding-box")
(setq *tfl* (instance ros::transform-listener :init))
(unless (boundp '*irtviewer*) (make-irtviewer))

(ros::subscribe *input-bbox-array* jsk_recognition_msgs::BoundingBoxArray
#'bounding-box-array-cb 1)
(do-until-key
(x::window-main-one)
(ros::spin-once)
(ros::sleep)
)