30 #include <gtest/gtest.h> 36 using std::stringstream;
87 for (
unsigned int i = 0; i <
sizeof(info_msg->R)/
sizeof(
double); i++)
93 for (
unsigned int i = 0; i <
sizeof(info_msg->P)/
sizeof(
double); i++)
103 uchar *infrared1_data = image.data;
105 double infrared1_total = 0.0;
106 int infrared1_count = 1;
107 for (
unsigned int i = 0; i < msg->height * msg->width; i++)
109 if (*infrared1_data > 0 && *infrared1_data < 255)
111 infrared1_total += *infrared1_data;
116 if (infrared1_count != 1)
118 g_infrared1_avg =
static_cast<float>(infrared1_total / infrared1_count);
124 for (
unsigned int i = 0; i < 5; i++)
136 uchar *infrared2_data = image.data;
138 double infrared2_total = 0.0;
139 int infrared2_count = 1;
140 for (
unsigned int i = 0; i < msg->height * msg->width; i++)
142 if (*infrared2_data > 0 && *infrared2_data < 255)
144 infrared2_total += *infrared2_data;
149 if (infrared2_count != 0)
151 g_infrared2_avg =
static_cast<float>(infrared2_total / infrared2_count);
157 for (
unsigned int i = 0; i < 5; i++)
165 void imageDepthCallback(
const sensor_msgs::ImageConstPtr &msg,
const sensor_msgs::CameraInfoConstPtr &info_msg)
168 uint16_t *image_data =
reinterpret_cast<uint16_t *
>(image.data);
170 double depth_total = 0;
172 for (
unsigned int i = 0; i < msg->height * msg->width; ++i)
174 if ((0 < *image_data) && (*image_data <=
g_max_z))
176 depth_total += *image_data;
181 if (depth_count != 0)
183 g_depth_avg =
static_cast<float>(depth_total / depth_count);
189 for (
unsigned int i = 0; i < 5; i++)
197 void imageColorCallback(
const sensor_msgs::ImageConstPtr &msg,
const sensor_msgs::CameraInfoConstPtr &info_msg)
201 uchar *color_data = image.data;
202 int64 color_total = 0;
204 for (
unsigned int i = 0; i < msg->height * msg->width * 3; i++)
206 if (*color_data > 0 && *color_data < 255)
208 color_total += *color_data;
213 if (color_count != 0)
215 g_color_avg =
static_cast<float>(color_total / color_count);
221 for (
unsigned int i = 0; i < 5; i++)
229 void imageFisheyeCallback(
const sensor_msgs::ImageConstPtr &msg,
const sensor_msgs::CameraInfoConstPtr &info_msg)
233 uchar *fisheye_data = image.data;
235 double fisheye_total = 0.0;
236 int fisheye_count = 1;
237 for (
unsigned int i = 0; i < msg->height * msg->width; i++)
239 if (*fisheye_data > 0 && *fisheye_data < 255)
241 fisheye_total += *fisheye_data;
246 if (fisheye_count != 0)
248 g_fisheye_avg =
static_cast<float>(fisheye_total / fisheye_count);
254 for (
unsigned int i = 0; i < 5; i++)
265 if (imu->angular_velocity_covariance[0] != -1.0)
267 if ((imu->angular_velocity.x != 0.0) ||
268 (imu->angular_velocity.y != 0.0) ||
269 (imu->angular_velocity.z != 0.0))
274 else if (imu->linear_acceleration_covariance[0] != -1.0)
276 if ((imu->linear_acceleration.x != 0.000) ||
277 (imu->linear_acceleration.y != 0.000) ||
278 (imu->linear_acceleration.z != 0.000))
287 pcl::PointCloud < pcl::PointXYZRGB > pointcloud;
290 double pc_depth_total = 0.0;
291 int pc_depth_count = 0;
292 for (
unsigned int i = 0; i < pointcloud.width * pointcloud.height; ++i)
294 pcl::PointXYZRGB point = pointcloud.points[i];
295 double pc_depth = std::ceil(point.z);
296 if ((0.0 < pc_depth) && (pc_depth <=
g_max_z))
298 pc_depth_total += pc_depth;
302 if (pc_depth_count != 0)
304 g_pc_depth_avg =
static_cast<float>(pc_depth_total / pc_depth_count);
310 TEST(RealsenseTests, testColorStream)
332 TEST(RealsenseTests, testColorResolution)
347 TEST(RealsenseTests, testColorCameraInfo)
353 EXPECT_STREQ(
g_dmodel_recv[RS_STREAM_COLOR].c_str(),
"plumb_bob");
378 bool any_are_zero =
false;
380 for (
unsigned int i = 0; i < 4; i++)
387 EXPECT_FALSE(any_are_zero);
392 TEST(RealsenseTests, testIsDepthStreamEnabled)
404 TEST(RealsenseTests, testDepthStream)
426 TEST(RealsenseTests, testDepthResolution)
441 TEST(RealsenseTests, testDepthCameraInfo)
447 EXPECT_STREQ(
g_dmodel_recv[RS_STREAM_DEPTH].c_str(),
"plumb_bob");
472 bool any_are_zero =
false;
473 for (
unsigned int i = 0; i < 5; i++)
480 EXPECT_FALSE(any_are_zero);
485 TEST(RealsenseTests, testInfrared1Stream)
506 TEST(RealsenseTests, testInfrared1Resolution)
521 TEST(RealsenseTests, testInfrared1CameraInfo)
527 EXPECT_STREQ(
g_dmodel_recv[RS_STREAM_INFRARED].c_str(),
"plumb_bob");
552 bool any_are_zero =
false;
553 for (
unsigned int i = 0; i < 5; i++)
560 EXPECT_FALSE(any_are_zero);
565 TEST(RealsenseTests, testInfrared2Stream)
582 TEST(RealsenseTests, testInfrared2Resolution)
601 TEST(RealsenseTests, testInfrared2CameraInfo)
610 EXPECT_STREQ(
g_dmodel_recv[RS_STREAM_INFRARED2].c_str(),
"plumb_bob");
635 TEST(RealsenseTests, testFisheyeStream)
649 TEST(RealsenseTests, testFisheyeCameraInfo)
655 EXPECT_STREQ(
g_dmodel_recv[RS_STREAM_FISHEYE].c_str(),
"plumb_bob");
681 bool any_are_zero =
false;
682 for (
unsigned int i = 0; i < 1; i++)
689 EXPECT_FALSE(any_are_zero);
706 TEST(RealsenseTests, testPointCloud)
720 TEST(RealsenseTests, testTransforms)
757 TEST(RealsenseTests, testCameraOptions)
760 stringstream settings_ss(
g_setting_srv.response.configuration_str);
763 string setting_value;
765 while (getline (settings_ss, setting,
';'))
767 stringstream setting_ss(setting);
768 getline(setting_ss, setting_name,
':');
769 setting_value = (setting.substr(setting.rfind(
":") + 1));
772 int option_recv = atoi(setting_value.c_str());
773 int option_exp = atoi(
g_config_args.at(setting_name).c_str());
774 EXPECT_EQ(option_exp, option_recv) << setting_name;
779 TEST(RealsenseTests, testGetSettingsService)
785 TEST(RealsenseTests, testSetPowerOffService)
795 TEST(RealsenseTests, testSetPowerOnService)
805 TEST(RealsenseTests, testForcePowerOffService)
813 TEST(RealsenseTests, testIsPoweredService)
820 TEST(RealsenseTests, testForcePowerOnService)
830 std::vector<std::string>
args;
832 for (
int i = 1; i < argc; ++i)
834 args.push_back(argv[i]);
836 while (args.size() > 1)
840 args.erase(args.begin());
841 args.erase(args.begin());
848 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"camera_type",
g_config_args.at(
"camera_type").c_str());
855 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"enable_depth",
g_config_args.at(
"enable_depth").c_str());
856 if (strcmp((
g_config_args.at(
"enable_depth").c_str ()),
"true") == 0)
870 if (strcmp((
g_config_args.at(
"enable_ir").c_str ()),
"true") == 0)
883 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"enable_ir2",
g_config_args.at(
"enable_ir2").c_str());
884 if (strcmp((
g_config_args.at(
"enable_ir2").c_str ()),
"true") == 0)
896 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"depth_encoding",
g_config_args.at(
"depth_encoding").c_str());
901 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"depth_height",
g_config_args.at(
"depth_height").c_str());
906 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"depth_width",
g_config_args.at(
"depth_width").c_str());
911 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"depth_step",
g_config_args.at(
"depth_step").c_str());
918 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"enable_color",
g_config_args.at(
"enable_color").c_str());
919 if (strcmp((
g_config_args.at(
"enable_color").c_str ()),
"true") == 0)
930 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"color_encoding",
g_config_args.at(
"color_encoding").c_str());
935 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"color_height",
g_config_args.at(
"color_height").c_str());
940 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"color_width",
g_config_args.at(
"color_width").c_str());
945 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"color_step",
g_config_args.at(
"color_step").c_str());
952 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"enable_fisheye",
954 if (strcmp((
g_config_args.at(
"enable_fisheye").c_str()),
"true") == 0)
967 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"enable_imu",
969 if (strcmp((
g_config_args.at(
"enable_imu").c_str()),
"true") == 0)
982 ROS_INFO(
"RealSense Camera - Setting %s to %s",
"enable_pointcloud",
984 if (strcmp((
g_config_args.at(
"enable_pointcloud").c_str()),
"true") == 0)
996 int main(
int argc,
char **argv)
try 998 testing::InitGoogleTest(&argc, argv);
1052 return RUN_ALL_TESTS();
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string PC_TOPIC
const std::string DEFAULT_IR_FRAME_ID
std::string g_depth_encoding_exp
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceClient g_ispowered_srv_client
realsense_camera::IsPowered g_ispowered_srv
uint32_t g_step_recv[STREAM_COUNT]
std::string g_camera_type
const std::string DEFAULT_DEPTH_FRAME_ID
void imageDepthCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
double g_caminfo_rotation_recv[STREAM_COUNT][9]
double g_depth_caminfo_D_recv[5]
image_transport::CameraSubscriber g_camera_subscriber[STREAM_COUNT]
const std::string COLOR_NAMESPACE
uint32_t g_depth_step_exp
const std::string FISHEYE_NAMESPACE
const std::string IMU_NAMESPACE
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
const std::string DEFAULT_COLOR_FRAME_ID
const std::string DEFAULT_FISHEYE_FRAME_ID
GLenum GLenum GLsizei void * image
void fillConfigMap(int argc, char **argv)
double g_caminfo_projection_recv[STREAM_COUNT][12]
realsense_camera::SetPower g_setpower_srv
const std::string CAMERA_IS_POWERED_SERVICE
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void imageColorCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
int g_caminfo_height_recv[STREAM_COUNT]
const std::string DEFAULT_IR_OPTICAL_FRAME_ID
const std::string TYPE_8UC1
std::string g_encoding_recv[STREAM_COUNT]
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::ServiceClient g_settings_srv_client
realsense_camera::ForcePower g_forcepower_srv
int g_caminfo_width_recv[STREAM_COUNT]
void getMsgInfo(rs_stream stream, const sensor_msgs::ImageConstPtr &msg)
ros::Subscriber g_sub_imu
double g_color_caminfo_D_recv[5]
TEST(RealsenseTests, testColorStream)
uint32_t g_infrared1_step_exp
void imageFisheyeCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
ros::ServiceClient g_forcepower_srv_client
void imageInfrared2Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
double g_fisheye_caminfo_D_recv[5]
const std::string FISHEYE_TOPIC
std::string g_color_encoding_exp
const std::string IR2_TOPIC
void getCameraInfo(rs_stream stream, const sensor_msgs::CameraInfoConstPtr &info_msg)
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID
const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID
const std::string IR2_NAMESPACE
int main(int argc, char **argv)
realsense_camera::CameraConfiguration g_setting_srv
uint32_t g_color_step_exp
std::map< std::string, std::string > g_config_args
const std::string IR_TOPIC
const std::string DEFAULT_IMU_FRAME_ID
const std::string TYPE_16UC1
const std::string COLOR_TOPIC
const std::string IMU_TOPIC
const std::string DEFAULT_BASE_FRAME_ID
void imageInfrared1Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
int g_height_recv[STREAM_COUNT]
const std::string DEPTH_TOPIC
const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID
const std::string DEPTH_NAMESPACE
const double ROTATION_IDENTITY[]
#define ROS_INFO_STREAM(args)
const std::string DEFAULT_IR2_FRAME_ID
const std::string DEFAULT_IR2_OPTICAL_FRAME_ID
const std::string IR_NAMESPACE
void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc)
const std::string CAMERA_FORCE_POWER_SERVICE
ros::ServiceClient g_setpower_srv_client
void imuCallback(const sensor_msgs::ImuConstPtr &imu)
std::string g_dmodel_recv[STREAM_COUNT]
const std::string CAMERA_SET_POWER_SERVICE
const std::string SETTINGS_SERVICE
std::string g_infrared1_encoding_exp
ROSCPP_DECL void spinOnce()
double g_infrared1_caminfo_D_recv[5]
const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID
double g_infrared2_caminfo_D_recv[5]
int g_width_recv[STREAM_COUNT]