Skip to content
This repository was archived by the owner on Nov 17, 2020. It is now read-only.

Commit b07f2df

Browse files
committed
Coding style corrections
1 parent 0c6fb4d commit b07f2df

File tree

4 files changed

+43
-47
lines changed

4 files changed

+43
-47
lines changed

CMakeLists.txt

Lines changed: 17 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,21 @@ else()
1717
endif()
1818
###############################################################################
1919

20-
find_package(ZED REQUIRED)
20+
find_package(ZED 1.0 REQUIRED)
21+
22+
##For Jetson, OpenCV4Tegra is based on OpenCV2.4
23+
exec_program(uname ARGS -p OUTPUT_VARIABLE CMAKE_SYSTEM_NAME2)
24+
if ( CMAKE_SYSTEM_NAME2 MATCHES "aarch64" OR CMAKE_SYSTEM_NAME2 MATCHES "armv7l" )
25+
SET(OCV_VERSION "2.4")
26+
SET(CUDA_VERSION "")
27+
else()
28+
SET(CUDA_VERSION "7.5")
29+
SET(OCV_VERSION "3.1")
30+
endif()
31+
32+
find_package(OpenCV ${OCV_VERSION} COMPONENTS core highgui imgproc REQUIRED)
33+
find_package(CUDA ${CUDA_VERSION} REQUIRED)
2134

22-
find_package(CUDA REQUIRED)
23-
find_package(OpenCV 3.1 EXACT REQUIRED COMPONENTS core highgui imgproc REQUIRED)
2435
find_package(PCL REQUIRED)
2536

2637
find_package(catkin REQUIRED COMPONENTS
@@ -41,7 +52,7 @@ catkin_package(
4152
roscpp
4253
rosconsole
4354
sensor_msgs
44-
opencv2
55+
opencv
4556
image_transport
4657
dynamic_reconfigure
4758
tf2_ros
@@ -52,7 +63,7 @@ catkin_package(
5263

5364
# Specify locations of header files.
5465
include_directories(
55-
${catkin_INCLUDE_DIRS}
66+
${catkin_INCLUDE_DIRS}
5667
${CUDA_INCLUDE_DIRS}
5768
${ZED_INCLUDE_DIRS}
5869
${OpenCV_INCLUDE_DIRS}
@@ -83,7 +94,7 @@ target_link_libraries(
8394
${ZED_LIBRARIES}
8495
${CUDA_LIBRARIES} ${CUDA_nppi_LIBRARY} ${CUDA_npps_LIBRARY}
8596
${OpenCV_LIBS}
86-
${PCL_LIBRARIES}
97+
${PCL_LIBRARIES}
8798
)
8899

89100
add_dependencies(zed_wrapper_node ${PROJECT_NAME}_gencfg)

README.md

Lines changed: 3 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ on the following ROS packages:
2929
- roscpp
3030
- rosconsole
3131
- sensor_msgs
32-
- opencv2
32+
- opencv
3333
- image_transport
3434
- dynamic_reconfigure
3535

@@ -55,7 +55,7 @@ Open a terminal :
5555
$ rosrun image_view image_view image:=/camera/rgb/image_rect_color
5656

5757
If you want to see the point cloud, lauch rviz with the following command. Then click on **add** (bottom left), select the **By Topic** tab, select **point_cloud->cloud->PointCloud2** and click **OK**.
58-
58+
5959
$ rosrun rviz rviz
6060

6161
Note that rviz isn't very good at displaying a camera feed and a point cloud at the same time. You should use an other instance of rviz or the `rosrun` command.
@@ -84,7 +84,7 @@ Open a terminal :
8484
sensing_mode | Depth sensing mode | '0': FILL
8585
_ | _ | '1': STANDARD
8686
openni_depth_mode | Convert depth to 16bit in millimeters | '0': 32bit float meters
87-
_ | _ | '1': 16bit uchar millimeters
87+
_ | _ | '1': 16bit uchar millimeters
8888
frame_rate | Rate at which images are published | int
8989
rgb_topic | Topic to which rgb==default==left images are published | string
9090
rgb_cam_info_topic | Topic to which rgb==default==left camera info are published | string
@@ -103,15 +103,3 @@ Open a terminal :
103103
odometry_topic | Topic to which odometry is published | string
104104
odometry_frame_id | ID specified in the odometry message header | string
105105
odometry_transform_frame_id | Name of the transformation following the odometry | string
106-
107-
108-
109-
110-
111-
112-
113-
114-
115-
116-
117-

package.xml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package>
33
<name>zed_wrapper</name>
4-
<version>0.1.0</version>
4+
<version>1.0.0</version>
55
<description>zed_wrapper is a ROS wrapper for the <a href="http://www.stereolabs.com/developers/">ZED library</a>
66
for interfacing with the ZED camera.
77
</description>
@@ -15,7 +15,7 @@
1515
<build_depend>roscpp</build_depend>
1616
<build_depend>rosconsole</build_depend>
1717
<build_depend>sensor_msgs</build_depend>
18-
<build_depend>opencv2</build_depend>
18+
<build_depend>opencv</build_depend>
1919
<build_depend>image_transport</build_depend>
2020
<build_depend>dynamic_reconfigure</build_depend>
2121

@@ -24,7 +24,7 @@
2424
<run_depend>roscpp</run_depend>
2525
<run_depend>rosconsole</run_depend>
2626
<run_depend>sensor_msgs</run_depend>
27-
<run_depend>opencv2</run_depend>
27+
<run_depend>opencv</run_depend>
2828
<run_depend>image_transport</run_depend>
2929
<run_depend>dynamic_reconfigure</run_depend>
3030

src/zed_wrapper_node.cpp

Lines changed: 20 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -104,11 +104,11 @@ bool file_exist(const std::string& name) {
104104
sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, const std::string encodingType, std::string frameId, ros::Time t){
105105
sensor_msgs::ImagePtr ptr = boost::make_shared<sensor_msgs::Image>();
106106
sensor_msgs::Image& imgMessage = *ptr;
107-
imgMessage.header.stamp=t;
108-
imgMessage.header.frame_id=frameId;
107+
imgMessage.header.stamp = t;
108+
imgMessage.header.frame_id = frameId;
109109
imgMessage.height = img.rows;
110110
imgMessage.width = img.cols;
111-
imgMessage.encoding=encodingType;
111+
imgMessage.encoding = encodingType;
112112
int num = 1; //for endianness detection
113113
imgMessage.is_bigendian = !(*(char *)&num == 1);
114114
imgMessage.step = img.cols * img.elemSize();
@@ -141,10 +141,10 @@ void publishOdom(Eigen::Matrix4f Path, ros::Publisher &pub_odom, string odom_fra
141141
odom.header.frame_id = odom_frame_id;
142142
//odom.child_frame_id = "zed_optical_frame";
143143

144-
odom.pose.pose.position.y = -Path(0,3);
145-
odom.pose.pose.position.z = Path(1,3);
146-
odom.pose.pose.position.x = -Path(2,3);
147-
Eigen::Quaternionf quat(Path.block<3,3>(0,0));
144+
odom.pose.pose.position.y = -Path(0, 3);
145+
odom.pose.pose.position.z = Path(1, 3);
146+
odom.pose.pose.position.x = -Path(2, 3);
147+
Eigen::Quaternionf quat(Path.block<3, 3>(0, 0));
148148
odom.pose.pose.orientation.x = -quat.z();
149149
odom.pose.pose.orientation.y = -quat.x();
150150
odom.pose.pose.orientation.z = quat.y();
@@ -164,10 +164,10 @@ void publishTrackedFrame(Eigen::Matrix4f Path, tf2_ros::TransformBroadcaster &tr
164164
transformStamped.header.stamp = ros::Time::now();
165165
transformStamped.header.frame_id = "zed_initial_frame";
166166
transformStamped.child_frame_id = odometry_transform_frame_id;
167-
transformStamped.transform.translation.x = -Path(0,3);
168-
transformStamped.transform.translation.y = Path(1,3);
169-
transformStamped.transform.translation.z = -Path(2,3);
170-
Eigen::Quaternionf quat(Path.block<3,3>(0,0));
167+
transformStamped.transform.translation.x = -Path(0, 3);
168+
transformStamped.transform.translation.y = Path(1, 3);
169+
transformStamped.transform.translation.z = -Path(2, 3);
170+
Eigen::Quaternionf quat(Path.block<3, 3>(0, 0));
171171
transformStamped.transform.rotation.x = -quat.z();
172172
transformStamped.transform.rotation.y = -quat.x();
173173
transformStamped.transform.rotation.z = quat.y();
@@ -363,7 +363,7 @@ int main(int argc, char **argv) {
363363
string right_frame_id = "/zed_tracked_frame";
364364

365365
string depth_topic = "depth/";
366-
if(openniDepthMode)
366+
if (openniDepthMode)
367367
depth_topic += "image_raw";
368368
else
369369
depth_topic += img_topic;
@@ -391,7 +391,7 @@ int main(int argc, char **argv) {
391391
nh_ns.getParam("frame_rate", rate);
392392
nh_ns.getParam("odometry_DB", odometry_DB);
393393
nh_ns.getParam("openni_depth_mode", openniDepthMode);
394-
if(openniDepthMode)
394+
if (openniDepthMode)
395395
ROS_INFO_STREAM("Openni depth mode activated");
396396

397397
nh_ns.getParam("rgb_topic", rgb_topic);
@@ -441,7 +441,7 @@ int main(int argc, char **argv) {
441441
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
442442
}
443443

444-
zed->grab(static_cast<sl::zed::SENSING_MODE> (sensing_mode), true, true, true);//call the first grab
444+
zed->grab(static_cast<sl::zed::SENSING_MODE> (sensing_mode), true, true, true); //call the first grab
445445

446446
//Tracking variables
447447
sl::zed::TRACKING_STATE track_state;
@@ -526,15 +526,14 @@ int main(int argc, char **argv) {
526526
bool runLoop = (rgb_SubNumber + left_SubNumber + right_SubNumber + depth_SubNumber + cloud_SubNumber + odom_SubNumber) > 0;
527527
// Run the loop only if there is some subscribers
528528
if (runLoop) {
529-
if(odom_SubNumber>0 && !tracking_activated) { //Start the tracking
530-
if(odometry_DB != "" && !file_exist(odometry_DB)){
529+
if (odom_SubNumber > 0 && !tracking_activated) { //Start the tracking
530+
if (odometry_DB != "" && !file_exist(odometry_DB)) {
531531
odometry_DB = "";
532532
ROS_WARN("odometry_DB path doesn't exist or is unreachable.");
533533
}
534534
zed->enableTracking(Path, true, odometry_DB);
535535
tracking_activated = true;
536-
}
537-
else if(odom_SubNumber==0 && tracking_activated) { //Stop the tracking
536+
} else if (odom_SubNumber == 0 && tracking_activated) { //Stop the tracking
538537
zed->stopTracking();
539538
tracking_activated = false;
540539
}
@@ -570,10 +569,10 @@ int main(int argc, char **argv) {
570569
ROS_INFO_STREAM(errcode2str(err));
571570
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
572571
}
573-
zed->grab(static_cast<sl::zed::SENSING_MODE> (sensing_mode), true, true, cloud_SubNumber > 0);//call the first grab
572+
zed->grab(static_cast<sl::zed::SENSING_MODE> (sensing_mode), true, true, cloud_SubNumber > 0); //call the first grab
574573
tracking_activated = false;
575-
if(odom_SubNumber>0) { //Start the tracking
576-
if(odometry_DB != "" && !file_exist(odometry_DB)){
574+
if (odom_SubNumber > 0) { //Start the tracking
575+
if (odometry_DB != "" && !file_exist(odometry_DB)) {
577576
odometry_DB = "";
578577
ROS_WARN("odometry_DB path doesn't exist or is unreachable.");
579578
}
@@ -640,8 +639,6 @@ int main(int argc, char **argv) {
640639
publishTrackedFrame(Path, transform_odom_broadcaster, odometry_transform_frame_id, ros::Time::now()); //publish the tracked Frame before the sleep
641640
std::this_thread::sleep_for(std::chrono::milliseconds(10)); // No subscribers, we just wait
642641
}
643-
644-
645642
}
646643
} catch (...) {
647644
if (pointCloudThread && pointCloudThreadRunning) {

0 commit comments

Comments
 (0)