A great place to start is: this question
If the tutorial linked there is insufficient for your needs, the bag_to_video code linked to there should give you the appropriate template for creating a tool to suit you.
Edit
Actually more informative code can be found here. See in particular the lines opening the bag and looping over its messages:
00068 // Load input bag file
00069 rosbag::Bag bag;
00070 bag.open(bag_in_name, rosbag::bagmode::Read);
00071 ROS_INFO("Opened %s", bag_in_name.c_str());
00072
00073 // Create output bag file
00074 rosbag::Bag bag_out;
00075 bag_out.open(bag_out_name, rosbag::bagmode::Write);
00076 ROS_INFO("Created %s", bag_out_name.c_str());
00077
00078 // Get topics
00079 rosbag::View view(bag);
00080
00081 // Loop over messages
00082 BOOST_FOREACH(rosbag::MessageInstance const m, view) {
00083
00084 // Get data
00085 sensor_msgs::ImageConstPtr image_msg = m.instantiate<sensor_msgs::Image>();
The part converting this to an OpenCV image:
00091 if (image_msg != NULL) {
00092
00093 cv::Mat image;
00094
00095 if (image_msg->encoding == "32FC1") { // depth image
00096 cv_bridge::CvImagePtr depth_image_ptr;
00097 try {
00098 depth_image_ptr = cv_bridge::toCvCopy(image_msg);
00099 } catch (cv_bridge::Exception& e) {
00100 ROS_ERROR("cv_bridge exception: %s", e.what());
00101 }
And the part reading the pixels off this image:
00105 for(int y = 0; y < depth_image_ptr->image.rows; y++) {
00106 for(int x = 0; x < depth_image_ptr->image.cols; x++) {
00107 float distance = depth_image_ptr->image.at<float>(y, x);