Skip to content

Commit

Permalink
Add support for floating point fps (#866)
Browse files Browse the repository at this point in the history
Related with this PR
#723

---------

Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jan 19, 2024
1 parent 21e5f25 commit e549e45
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion image_view/include/image_view/video_recorder_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions image_view/src/video_recorder_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -111,7 +111,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);
}

Expand Down

0 comments on commit e549e45

Please sign in to comment.