ros-perception / opencv_apps

http://wiki.ros.org/opencv_apps
64 stars 70 forks source link

force convert to bgr for display #30

Closed k-okada closed 7 years ago

k-okada commented 8 years ago

@wkentaro please review, and do I have to change other codes as well? I do not use cvtColorForDisplay because someone still want to compile this on hydro.

$ grep toCvS ../src/nodelet/*
../src/nodelet/adding_images_nodelet.cpp:          cv_bridge::toCvShare(image_msg1, image_msg1->encoding)->image;
../src/nodelet/adding_images_nodelet.cpp:          cv_bridge::toCvShare(image_msg2, image_msg2->encoding)->image;
../src/nodelet/camshift_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, "bgr8")->image;
../src/nodelet/contour_moments_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/convex_hull_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/edge_detection_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/face_detection_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/fback_flow_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/find_contours_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/general_contours_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/goodfeature_track_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/hough_circles_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/hough_lines_nodelet.cpp:      cv::Mat in_image = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/lk_flow_nodelet.cpp:      cv::Mat image = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/people_detect_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/phase_corr_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/segment_objects_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/simple_flow_nodelet.cpp:      cv::Mat frame_src = cv_bridge::toCvShare(msg, msg->encoding)->image;
../src/nodelet/threshold_nodelet.cpp:          cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
../src/nodelet/watershed_segmentation_nodelet.cpp:      cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
wkentaro commented 8 years ago

+1

k-okada commented 8 years ago

thanks, I confirmed with

$ roslaunch jsk_perception sample_image_publisher.launch gui:=false
$ rostopic echo /raw_image_bgr/image_color --noarr  # bgr8
$ rostopic echo /raw_image_rgb/image_color --noarr  # rgb8

https://github.com/ros-perception/opencv_apps/commit/3ab28cf0bc07d4ce53537650bfd9cb59ab3be07f#commitcomment-18944207