Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

rework parameters for foxy #21

Merged
merged 1 commit into from
Nov 30, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions include/opencv_cam/camera_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ namespace opencv_cam
CXT_MACRO_MEMBER(camera_frame_id, std::string, "camera_frame") /* Camera frame id */ \
/* End of list */

#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_DEFINE_MEMBER(n, t, d)

struct CameraContext
{
OPENCV_CAM_ALL_PARAMS
#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_DEFINE_MEMBER(n, t, d)
CXT_MACRO_DEFINE_MEMBERS(OPENCV_CAM_ALL_PARAMS)
};

} // namespace opencv_cam
Expand Down
3 changes: 2 additions & 1 deletion include/opencv_cam/opencv_cam_node.hpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,14 @@
#ifndef OPENCV_CAM_HPP
#define OPENCV_CAM_HPP

#include "opencv_cam/camera_context.hpp"

#include "opencv2/highgui/highgui.hpp"
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/camera_info.hpp"
#include "sensor_msgs/msg/image.hpp"

#include "opencv_cam/camera_context.hpp"

namespace opencv_cam
{

Expand Down
28 changes: 17 additions & 11 deletions src/opencv_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,25 @@ namespace opencv_cam
{
RCLCPP_INFO(get_logger(), "use_intra_process_comms=%d", options.use_intra_process_comms());

// Get parameters
// Initialize parameters
#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_LOAD_PARAMETER((*this), cxt_, n, t, d)
CXT_MACRO_INIT_PARAMETERS(OPENCV_CAM_ALL_PARAMS, validate_parameters)

// Register parameters
// Register for parameter changed. NOTE at this point nothing is done when parameters change.
#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_PARAMETER_CHANGED(cxt_, n, t)
CXT_MACRO_REGISTER_PARAMETERS_CHANGED((*this), OPENCV_CAM_ALL_PARAMS, validate_parameters)
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_PARAMETER_CHANGED(n, t)
CXT_MACRO_REGISTER_PARAMETERS_CHANGED((*this), cxt_, OPENCV_CAM_ALL_PARAMS, validate_parameters)

// Log the current parameters
#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_LOG_SORTED_PARAMETER(cxt_, n, t, d)
CXT_MACRO_LOG_SORTED_PARAMETERS(RCLCPP_INFO, get_logger(), "opencv_cam Parameters", OPENCV_CAM_ALL_PARAMS)

// Check that all command line parameters are registered
#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_CHECK_CMDLINE_PARAMETER(n, t, d)
CXT_MACRO_CHECK_CMDLINE_PARAMETERS((*this), OPENCV_CAM_ALL_PARAMS)

RCLCPP_INFO(get_logger(), "OpenCV version %d", CV_VERSION_MAJOR);

Expand All @@ -61,7 +71,7 @@ namespace opencv_cam
double width = capture_->get(cv::CAP_PROP_FRAME_WIDTH);
double height = capture_->get(cv::CAP_PROP_FRAME_HEIGHT);
RCLCPP_INFO(get_logger(), "file %s open, width %g, height %g, publish fps %d",
cxt_.filename_.c_str(), width, height, publish_fps_);
cxt_.filename_.c_str(), width, height, publish_fps_);

next_stamp_ = now();

Expand Down Expand Up @@ -89,7 +99,7 @@ namespace opencv_cam
double height = capture_->get(cv::CAP_PROP_FRAME_HEIGHT);
double fps = capture_->get(cv::CAP_PROP_FPS);
RCLCPP_INFO(get_logger(), "device %d open, width %g, height %g, device fps %g",
cxt_.index_, width, height, fps);
cxt_.index_, width, height, fps);
}

assert(!cxt_.camera_info_path_.empty()); // readCalibration will crash if file_name is ""
Expand Down Expand Up @@ -121,11 +131,7 @@ namespace opencv_cam
}

void OpencvCamNode::validate_parameters()
{
#undef CXT_MACRO_MEMBER
#define CXT_MACRO_MEMBER(n, t, d) CXT_MACRO_LOG_PARAMETER(RCLCPP_INFO, get_logger(), cxt_, n, t, d)
OPENCV_CAM_ALL_PARAMS
}
{}

void OpencvCamNode::loop()
{
Expand Down