Skip to content

Commit

Permalink
Merge pull request #143 from mdhorn/rostest-fix-zr300
Browse files Browse the repository at this point in the history
Fix ROS Camera Tests
  • Loading branch information
mdhorn authored Oct 27, 2016
2 parents 5dc178f + f69749f commit 78a7716
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 11 deletions.
10 changes: 6 additions & 4 deletions realsense_camera/test/camera_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -608,6 +608,7 @@ TEST(RealsenseTests, testFisheyeStream)
{
if (g_enable_fisheye)
{
ROS_INFO_STREAM("RealSense Camera - fisheye_avg: " << g_fisheye_avg);
EXPECT_TRUE(g_fisheye_avg > 0);
EXPECT_TRUE(g_fisheye_recv);
}
Expand All @@ -619,7 +620,7 @@ TEST(RealsenseTests, testFisheyeStream)

TEST(RealsenseTests, testFisheyeCameraInfo)
{
if (g_enable_imu)
if (g_enable_fisheye)
{
EXPECT_EQ(g_width_recv[RS_STREAM_FISHEYE], g_caminfo_width_recv[RS_STREAM_FISHEYE]);
EXPECT_EQ(g_height_recv[RS_STREAM_FISHEYE], g_caminfo_height_recv[RS_STREAM_FISHEYE]);
Expand All @@ -645,11 +646,12 @@ TEST(RealsenseTests, testFisheyeCameraInfo)
EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][10] != 0.0);
EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][11], 0.0);

// SR300 cameras have Fisheye distortion parameters
if (g_camera_type == "SR300")
// ZR300 cameras have Fisheye distortion parameters
// Only the first coefficient is used/valid
if (g_camera_type == "ZR300")
{
bool any_are_zero = false;
for (unsigned int i = 0; i < 5; i++)
for (unsigned int i = 0; i < 1; i++)
{
if (g_fisheye_caminfo_D_recv[i] == 0.0)
{
Expand Down
4 changes: 2 additions & 2 deletions realsense_camera/test/camera_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ uint32_t g_infrared1_step_exp; // Expected infrared1 step.

bool g_enable_color = true;
bool g_enable_depth = true;
bool g_enable_fisheye = true;
bool g_enable_imu = true;
bool g_enable_fisheye = false;
bool g_enable_imu = false;
bool g_enable_pointcloud = false;

std::string g_depth_encoding_exp; // Expected depth encoding.
Expand Down
14 changes: 9 additions & 5 deletions realsense_camera/test/zr300_nodelet_default.test
Original file line number Diff line number Diff line change
@@ -1,14 +1,18 @@
<launch>
<arg name="camera" value="camera" />
<arg name="camera_type" default="ZR300" />
<arg name="camera" value="camera" />
<arg name="camera_type" default="ZR300" />
<arg name="enable_fisheye" default="true" />
<arg name="enable_imu" default="true" />

<!-- Start camera -->
<include file="$(find realsense_camera)/launch/zr300_nodelet_default.launch">
<arg name="camera" value="$(arg camera)" />
<arg name="camera_type" value="$(arg camera_type)" />
<arg name="camera" value="$(arg camera)" />
<arg name="camera_type" value="$(arg camera_type)" />
</include>

<!-- Start test -->
<test pkg="realsense_camera" type="tests_camera_core" test-name="realsense_camera_test"
args="camera_type $(arg camera_type)" />
args="camera_type $(arg camera_type)
enable_fisheye $(arg enable_fisheye)
enable_imu $(arg enable_imu)" />
</launch>

0 comments on commit 78a7716

Please sign in to comment.