Skip to content

Commit

Permalink
fixing the warning for VGA resolution
Browse files Browse the repository at this point in the history
  • Loading branch information
Natalia Lyubova committed Nov 21, 2017
1 parent fbffefe commit 298aece
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 1 deletion.
1 change: 1 addition & 0 deletions CMakeLists_catkin.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(catkin COMPONENTS
naoqi_libqicore
robot_state_publisher
rosbag_storage
rosconsole
rosgraph_msgs
sensor_msgs
tf2_geometry_msgs
Expand Down
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<build_depend>orocos_kdl</build_depend>
<build_depend>robot_state_publisher</build_depend>
<build_depend>rosbag_storage</build_depend>
<build_depend>rosconsole</build_depend>
<build_depend>rosgraph_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>tf2_geometry_msgs</build_depend>
Expand All @@ -41,6 +42,7 @@
<run_depend>orocos_kdl</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rosbag_storage</run_depend>
<run_depend>rosconsole</run_depend>
<run_depend>tf2_ros</run_depend>

<conflict>nao_driver</conflict>
Expand Down
3 changes: 2 additions & 1 deletion src/converters/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
* ROS includes
*/
#include <cv_bridge/cv_bridge.h>
#include <ros/console.h>

/*
* CV includes
Expand Down Expand Up @@ -99,7 +100,7 @@ const sensor_msgs::CameraInfo& getCameraInfo( int camera_source, int resolution
if ( resolution == AL::kVGA )
{
static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHVGA();
ROS_WARN("VGA resolution is not supported for the depth camera, please use QVGA");
ROS_WARN("VGA resolution is not supported for the depth camera, use QVGA or lower");
return cam_info_msg;
}
else if( resolution == AL::kQVGA )
Expand Down

0 comments on commit 298aece

Please sign in to comment.