diff --git a/image_view/include/image_view/video_recorder_node.hpp b/image_view/include/image_view/video_recorder_node.hpp index cf6ca784a..52d6b5bd7 100644 --- a/image_view/include/image_view/video_recorder_node.hpp +++ b/image_view/include/image_view/video_recorder_node.hpp @@ -43,7 +43,7 @@ class VideoRecorderNode rclcpp::Time g_last_wrote_time; std::string encoding; std::string codec; - int fps; + double fps; double min_depth_range; double max_depth_range; bool use_dynamic_range; diff --git a/image_view/src/video_recorder_node.cpp b/image_view/src/video_recorder_node.cpp index d10aa593c..6c8a44b28 100644 --- a/image_view/src/video_recorder_node.cpp +++ b/image_view/src/video_recorder_node.cpp @@ -42,7 +42,7 @@ VideoRecorderNode::VideoRecorderNode(const rclcpp::NodeOptions & options) filename = this->declare_parameter("filename", std::string("output.avi")); stamped_filename = this->declare_parameter("stamped_filename", false); - fps = this->declare_parameter("fps", 15); + fps = this->declare_parameter("fps", 15.0); codec = this->declare_parameter("codec", std::string("MJPG")); encoding = this->declare_parameter("encoding", std::string("bgr8")); // cv_bridge::CvtColorForDisplayOptions @@ -108,7 +108,7 @@ void VideoRecorderNode::callback(const sensor_msgs::msg::Image::ConstSharedPtr & RCLCPP_INFO( this->get_logger(), - "Starting to record %s video at %ix%i@%i fps. Press Ctrl+C to stop recording.", + "Starting to record %s video at %ix%i@%.2f fps. Press Ctrl+C to stop recording.", codec.c_str(), size.height, size.width, fps); }