Skip to content

Commit

Permalink
Merge branch 'master' into panorama-sample-launch-refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
knorth55 committed Jan 24, 2023
2 parents 0e0cea3 + 38ef7b5 commit 44c267d
Show file tree
Hide file tree
Showing 49 changed files with 446 additions and 231 deletions.
21 changes: 17 additions & 4 deletions .github/workflows/config.yml
Expand Up @@ -66,16 +66,29 @@ jobs:
NOT_TEST_INSTALL : true
USE_JENKINS: true
DOCKER_IMAGE_JENKINS: ros-ubuntu:20.04-pcl
TEST_PKGS : 'jsk_recognition_msgs' # to skip test
BEFORE_SCRIPT : "sudo pip install numpy==1.16.6; sudo pip install fcn chainercv chainer-mask-rcnn==0.3.0 decorator==4.4.2 chainer==6.7.0 protobuf==3.18.0 cupy-cuda91 pytesseract==0.3.6 torch==1.4.0;"
BEFORE_SCRIPT : "sudo pip3 install numpy==1.17.5 scipy==1.3.3 scikit-image==0.16.2 PyWavelets==0.5.1 imageio==2.4.1 pandas==0.25.3; sudo pip3 install fcn chainercv chainer-mask-rcnn==0.3.0 decorator==4.4.2 chainer==7.8.1 protobuf==3.6.1 cupy-cuda91 pytesseract==0.3.10 Pillow==9.3.0 torch==1.4.0 torchvision==0.5.0;sudo dpkg -i /workspace/.ros/data/libpcl-features1.10_1.10.0+dfsg-5ubuntu1_amd64.deb;"
BUILD_PKGS: 'checkerboard_detector imagesift jsk_perception jsk_recognition_utils resized_image_transport'
EXTRA_DEB: ros-noetic-pr2-description
experimental : false
- ROS_DISTRO: noetic
USE_DEB: false
NOT_TEST_INSTALL : true
USE_JENKINS: true
DOCKER_IMAGE_JENKINS: ros-ubuntu:20.04-pcl
BEFORE_SCRIPT : "sudo pip install numpy==1.16.6; sudo pip install fcn chainercv chainer-mask-rcnn==0.3.0 decorator==4.4.2 chainer==6.7.0 protobuf==3.18.0 cupy-cuda91 pytesseract==0.3.6 torch==1.4.0;"
experimental : true
TEST_PKGS : 'jsk_pcl_ros_utils jsk_pcl_ros'
BEFORE_SCRIPT : "sudo pip3 install numpy==1.17.5 scipy==1.3.3 scikit-image==0.16.2 PyWavelets==0.5.1 imageio==2.4.1 pandas==0.25.3; sudo pip3 install fcn chainercv chainer-mask-rcnn==0.3.0 decorator==4.4.2 chainer==7.8.1 protobuf==3.6.1 cupy-cuda91 pytesseract==0.3.10 Pillow==9.3.0 torch==1.4.0 torchvision==0.5.0;sudo dpkg -i /workspace/.ros/data/libpcl-features1.10_1.10.0+dfsg-5ubuntu1_amd64.deb;"
BUILD_PKGS: 'jsk_pcl_ros_utils jsk_pcl_ros'
EXTRA_DEB: ros-noetic-pr2-description
experimental : false
- ROS_DISTRO: noetic
USE_DEB: false
NOT_TEST_INSTALL : true
USE_JENKINS: true
DOCKER_IMAGE_JENKINS: ros-ubuntu:20.04-pcl
TEST_PKGS : 'jsk_recognition_msgs' # to skip test
BEFORE_SCRIPT : "sudo pip3 install numpy==1.17.5 scipy==1.3.3 scikit-image==0.16.2 PyWavelets==0.5.1 imageio==2.4.1 pandas==0.25.3; sudo pip3 install fcn chainercv chainer-mask-rcnn==0.3.0 decorator==4.4.2 chainer==7.8.1 protobuf==3.6.1 cupy-cuda91 pytesseract==0.3.10 Pillow==9.3.0 torch==1.4.0 torchvision==0.5.0;sudo dpkg -i /workspace/.ros/data/libpcl-features1.10_1.10.0+dfsg-5ubuntu1_amd64.deb;"
EXTRA_DEB: ros-noetic-pr2-description
experimental : false


steps:
Expand Down
4 changes: 4 additions & 0 deletions .travis.rosinstall.noetic
@@ -0,0 +1,4 @@
- git: # https://github.com/ros-perception/image_transport_plugins/pull/64
uri: https://github.com/ros-perception/image_transport_plugins.git
local-name: image_transport_plugins
version: noetic-devel
3 changes: 2 additions & 1 deletion imagesift/test/test_imagesift.test
Expand Up @@ -6,7 +6,8 @@

<test test-name="test_imagesift"
name="test_imagesift"
pkg="jsk_tools" type="test_topic_published.py">
pkg="jsk_tools" type="test_topic_published.py"
retry="3">
<rosparam>
topic_0: /Feature0D
timeout_0: 10
Expand Down
28 changes: 26 additions & 2 deletions jsk_pcl_ros/CMakeLists.txt
Expand Up @@ -140,7 +140,7 @@ generate_dynamic_reconfigure_options(

find_package(OpenCV REQUIRED core imgproc)

include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} ${ml_classifiers_INCLUDE_DIRS})
link_directories(${catkin_LIBRARY_DIRS})
if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "GNU")
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -z defs")
Expand Down Expand Up @@ -505,10 +505,34 @@ install(TARGETS ${jsk_pcl_ros_install_libraries}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)

install(DIRECTORY config euslisp launch plugins sample scripts test
install(DIRECTORY config euslisp launch plugins test
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)
if($ENV{ROS_DISTRO} STREQUAL "indigo") # on noetic it needs catkin_install_python to support Python3 and it does not work on indigo for some reason...
install(DIRECTORY sample scripts
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)
else()
install(DIRECTORY sample scripts
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
PATTERN "*"
PATTERN "*/*.py" EXCLUDE
)

file(GLOB SCRIPT_PROGRAMS scripts/*.py)
catkin_install_python(
PROGRAMS ${SCRIPT_PROGRAMS}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts
)
file(GLOB SAMPLE_SCRIPT_PROGRAMS sample/*.py)
catkin_install_python(
PROGRAMS ${SAMPLE_SCRIPT_PROGRAMS}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/sample
)
endif()

if (CATKIN_ENABLE_TESTING)
find_package(jsk_perception REQUIRED)
Expand Down
2 changes: 2 additions & 0 deletions jsk_pcl_ros/package.xml
Expand Up @@ -91,6 +91,8 @@
<exec_depend>visualization_msgs</exec_depend>
<exec_depend>yaml-cpp</exec_depend>

<test_depend>compressed_depth_image_transport</test_depend>
<test_depend>compressed_image_transport</test_depend>
<test_depend>jsk_perception</test_depend>
<test_depend>jsk_tools</test_depend>
<test_depend>roslaunch</test_depend>
Expand Down
Expand Up @@ -6,11 +6,12 @@
<arg name="RGB_IMAGE" value="/camera/color/image_rect_color" />
<arg name="DEPTH_CAMERA_INFO" value="/camera/aligned_depth_to_color/camera_info" />
<arg name="DEPTH_IMAGE" value="/camera/aligned_depth_to_color/image_raw" />
<arg name="RATE" default="1.0" />

<param name="/use_sim_time" value="true"/>

<node name="rosbag_play" pkg="rosbag" type="play"
args="$(find jsk_pcl_ros)/sample/data/baxter_realsense_l515.bag --clock --loop"/>
args="--rate $(arg RATE) $(find jsk_pcl_ros)/sample/data/baxter_realsense_l515.bag --clock --loop"/>

<group ns="camera">
<group ns="color">
Expand Down
Expand Up @@ -3,7 +3,7 @@
<arg name="rosbag_play_args" default="--clock --loop" />

<param name="/use_sim_time" value="true"/>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pr2_description)/robots/pr2.urdf.xacro'"/>
<param name="robot_description" command="$(find xacro)/xacro '$(find pr2_description)/robots/pr2.urdf.xacro'"/>

<node name="rosbag_play"
pkg="rosbag" type="play"
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros/sample/sample_joint_state_static_filter.launch
Expand Up @@ -3,7 +3,7 @@
<arg name="gui" default="true"/>

<param name="/use_sim_time" value="true"/>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pr2_description)/robots/pr2.urdf.xacro'"/>
<param name="robot_description" command="$(find xacro)/xacro '$(find pr2_description)/robots/pr2.urdf.xacro'"/>

<node name="rosbag_play"
pkg="rosbag" type="play"
Expand Down
@@ -1,9 +1,11 @@
<launch>
<arg name="gui" default="true" />
<arg name="RATE" default="1.0" />

<include file="$(find jsk_pcl_ros)/sample/include/play_rosbag_baxter_realsense_l515.xml">
<arg name="launch_manager" value="true" />
<arg name="manager" value="realsense_nodelet_manager" />
<arg name="RATE" value="$(arg RATE)" />
</include>

<include file="$(find jsk_pcl_ros)/launch/organized_statistical_outlier_removal.launch">
Expand Down
Expand Up @@ -348,7 +348,7 @@ def updatePlot():
def generateFrequencyMap():
global width, height
# bgr
img = np.tile(np.uint8([0,0,0]), (height / 10, width / 10, 1))
img = np.tile(np.uint8([0,0,0]), (height // 10, width // 10, 1))
frequency = dict()
for (u, v) in value_cache.keys():
min_color = np.uint8([255, 0, 0])
Expand Down
2 changes: 2 additions & 0 deletions jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp
Expand Up @@ -207,6 +207,7 @@ namespace jsk_pcl_ros
std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res)
{
boost::mutex::scoped_lock lock(mutex_);
if (samples_.size() <= 1) {
ROS_ERROR("no enough samples");
return false;
Expand Down Expand Up @@ -251,6 +252,7 @@ namespace jsk_pcl_ros
nonregistered_ros_cloud.header.stamp = ros::Time::now();
nonregistered_ros_cloud.header.frame_id = frame_id_;
pub_cloud_non_registered_.publish(nonregistered_ros_cloud);
return true;
}

}
Expand Down
Expand Up @@ -92,7 +92,7 @@
<test test-name="test_cluster_point_indices_decomposer_bbox"
name="test_cluster_point_indices_decomposer_bbox"
pkg="jsk_pcl_ros" type="test_cluster_point_indices_decomposer_bbox.py"
time-limit="30" retry="1">
time-limit="30" retry="3">
<remap from="~boxes" to="cluster_point_indices_decomposer/boxes" />
<rosparam>
check_times: 10
Expand All @@ -102,7 +102,7 @@
<test test-name="test_cluster_point_indices_decomposer_bbox_align_boxes_with_frame"
name="test_cluster_point_indices_decomposer_bbox_align_boxes_with_frame"
pkg="jsk_pcl_ros" type="test_cluster_point_indices_decomposer_bbox.py"
time-limit="30" retry="1">
time-limit="30" retry="3">
<remap from="~boxes" to="cluster_point_indices_decomposer_align_boxes_with_frame/boxes" />
<rosparam>
check_times: 10
Expand All @@ -112,7 +112,7 @@
<test test-name="test_cluster_point_indices_decomposer_bbox_pca"
name="test_cluster_point_indices_decomposer_bbox_pca"
pkg="jsk_pcl_ros" type="test_cluster_point_indices_decomposer_bbox.py"
time-limit="30" retry="1">
time-limit="30" retry="3">
<remap from="~boxes" to="cluster_point_indices_decomposer_pca/boxes" />
<rosparam>
check_times: 10
Expand Down
3 changes: 2 additions & 1 deletion jsk_pcl_ros/test/test_convex_connected_voxels.test
Expand Up @@ -12,7 +12,8 @@

<test test-name="test_convex_connected_voxels"
name="test_convex_connected_voxels"
pkg="jsk_tools" type="test_topic_published.py">
pkg="jsk_tools" type="test_topic_published.py"
retry="3" time-limit="120">
<rosparam>
topic_0: /sample_convex_connected_voxels/output/indices
timeout_0: 100
Expand Down
Expand Up @@ -2,15 +2,16 @@

<include file="$(find jsk_pcl_ros)/sample/sample_organized_statistical_outlier_removal.launch">
<arg name="gui" value="false"/>
<arg name="RATE" value="0.25" />
</include>

<test test-name="test_organized_statistical_outlier_removal"
name="test_organized_statistical_outlier_removal"
pkg="jsk_tools" type="test_topic_published.py"
retry="3">
retry="3" time-limit="120">
<rosparam>
topic_0: /statistical_outlier_removal/output
timeout_0: 30
timeout_0: 100
</rosparam>
</test>

Expand Down
23 changes: 22 additions & 1 deletion jsk_pcl_ros_utils/scripts/cloud_on_plane_info.py
Expand Up @@ -6,6 +6,27 @@
from jsk_rviz_plugins.overlay_text_interface import OverlayTextInterface
from jsk_recognition_msgs.msg import BoolStamped

# workaround until https://github.com/jsk-ros-pkg/jsk_visualization/pull/864 is merged and released.
class OverlayTextInterface_fix(OverlayTextInterface):
def publish(self, text):
msg = OverlayText()
msg.text = text
msg.width = int(self.config.width)
msg.height = int(self.config.height)
msg.top = int(self.config.top)
msg.left = int(self.config.left)
msg.fg_color.a = self.config.fg_alpha
msg.fg_color.r = self.config.fg_red
msg.fg_color.g = self.config.fg_green
msg.fg_color.b = self.config.fg_blue
msg.bg_color.a = self.config.bg_alpha
msg.bg_color.r = self.config.bg_red
msg.bg_color.g = self.config.bg_green
msg.bg_color.b = self.config.bg_blue
msg.text_size = self.config.text_size
self.pub.publish(msg)


g_lock = Lock()
g_msg = None
def callback(msg):
Expand All @@ -23,7 +44,7 @@ def publish_text(event):

if __name__ == "__main__":
rospy.init_node("cloud_on_plane_info")
text_interface = OverlayTextInterface("~text")
text_interface = OverlayTextInterface_fix("~text")
sub = rospy.Subscriber("~input", BoolStamped, callback)
rospy.Timer(rospy.Duration(0.1), publish_text)
rospy.spin()
14 changes: 10 additions & 4 deletions jsk_perception/CMakeLists.txt
Expand Up @@ -41,9 +41,7 @@ find_package(catkin REQUIRED COMPONENTS

find_package(roseus)

if(NOT $ENV{ROS_DISTRO} STREQUAL "indigo") # on noetic it needs catkin_install_python to support Python3 and it does not work on indigo for some reason...
catkin_python_setup()
endif()
catkin_python_setup()

find_package(Boost REQUIRED COMPONENTS filesystem system)

Expand Down Expand Up @@ -447,9 +445,17 @@ catkin_install_python(
PROGRAMS ${NODE_SCRIPT_PROGRAMS}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/node_scripts
)
if(CATKIN_DEVEL_PREFIX)
add_custom_target(link_dir_mkdir
COMMAND ${CMAKE_COMMAND} -E make_directory ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/node_scripts)
foreach(SUB_DIR craft deep_sort hmr openpose)
add_custom_target(link_dir_${SUB_DIR} ALL
COMMAND ${CMAKE_COMMAND} -E create_symlink ${PROJECT_SOURCE_DIR}/node_scripts/${SUB_DIR} ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/node_scripts/${SUB_DIR})
add_dependencies(link_dir_${SUB_DIR} link_dir_mkdir)
endforeach()
endif(CATKIN_DEVEL_PREFIX)
endif()


# ------------------------------------------------------------------------------------
# Test
# ------------------------------------------------------------------------------------
Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/node_scripts/alexnet_object_recognition.py
Expand Up @@ -30,7 +30,7 @@
from jsk_recognition_utils.chainermodels import AlexNetBatchNormalization
import rospy
from sensor_msgs.msg import Image
from vgg16_object_recognition import VGG16ObjectRecognition
from jsk_perception.vgg16_object_recognition import VGG16ObjectRecognition


class AlexNetObjectRecognition(VGG16ObjectRecognition):
Expand Down
2 changes: 2 additions & 0 deletions jsk_perception/node_scripts/binpack_rect_array.py
Expand Up @@ -24,6 +24,8 @@ def width_cmp(self, another):
return self.rect.width - another.rect.width
def __cmp__(self, another): # python2
return self.max_cmp(another) or self.min_cmp(another) or self.height_cmp(another) or self.width_cmp(another) or 0
def __lt__(self, another): # python3
return self.max_cmp(another) or self.min_cmp(another) or self.height_cmp(another) or self.width_cmp(another) or 0

class Packer():
def __init__(self):
Expand Down
22 changes: 16 additions & 6 deletions jsk_perception/node_scripts/bof_histogram_extractor.py
Expand Up @@ -5,8 +5,12 @@
"""

import gzip
import cPickle as pickle
from distutils.version import StrictVersion
import sys
if sys.version_info.major <= 2:
import cPickle as pickle
else: # for python3
import _pickle as pickle
from distutils.version import LooseVersion
from pkg_resources import get_distribution

import numpy as np
Expand Down Expand Up @@ -34,14 +38,20 @@ def __init__(self):
if bof_data is None:
quit()
with gzip.open(bof_data, 'rb') as f:
self.bof = pickle.load(f)
if (StrictVersion(get_distribution('scikit-learn').version) >=
StrictVersion('0.17.0')):
if sys.version_info.major <= 2:
self.bof = pickle.load(f)
else:
self.bof = pickle.load(f, encoding='latin1')
if (LooseVersion(get_distribution('scikit-learn').version) >=
LooseVersion('0.17')):
if 'n_jobs' not in self.bof.nn.__dict__ or not isinstance(self.bof.nn.n_jobs, int):
# In scikit-learn>=0.17.0,
# sklearn.neighbors.NearestNeighbors needs 'n_jobs' attribute.
# https://github.com/jsk-ros-pkg/jsk_recognition/issues/1669
self.bof.nn.n_jobs = 1
# noetic uses newer scikit-learn which uses n_samples_fit_
if 'n_ssamples_fit_' not in self.bof.nn.__dict__:
self.bof.nn.n_samples_fit_ = self.bof.nn._fit_X.shape[0]

self._pub = self.advertise('~output', VectorArray, queue_size=1)
rospy.loginfo('Initialized BoF histogram extractor')
Expand Down Expand Up @@ -79,7 +89,7 @@ def _apply(self, feature_msg, label_msg):
decomposed = decompose_descriptors_with_label(
descriptors=desc, positions=pos, label_img=label,
skip_zero_label=True)
X = np.array(decomposed.values())
X = np.array(list(decomposed.values()))
if X.size == 0:
return
X = self.bof.transform(X)
Expand Down

0 comments on commit 44c267d

Please sign in to comment.