From c5e954b56a68a5755367eaf3edf45b5ffb5713e0 Mon Sep 17 00:00:00 2001 From: Alexey Rogachevskiy Date: Tue, 26 May 2020 22:20:05 +0300 Subject: [PATCH] optical_flow: Use functional-style parameter fetching --- clover/src/optical_flow.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/clover/src/optical_flow.cpp b/clover/src/optical_flow.cpp index a85c03f36..616e2464e 100644 --- a/clover/src/optical_flow.cpp +++ b/clover/src/optical_flow.cpp @@ -64,11 +64,11 @@ class OpticalFlow : public nodelet::Nodelet tf_buffer_.reset(new tf2_ros::Buffer()); tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_, nh)); - nh.param("mavros/local_position/tf/frame_id", local_frame_id_, "map"); - nh.param("mavros/local_position/tf/child_frame_id", fcu_frame_id_, "base_link"); - nh_priv.param("roi", roi_px_, 128); - nh_priv.param("roi_rad", roi_rad_, 0.0); - nh_priv.param("calc_flow_gyro", calc_flow_gyro_, false); + local_frame_id_ = nh.param("mavros/local_position/tf/frame_id", "map"); + fcu_frame_id_ = nh.param("mavros/local_position/tf/child_frame_id", "base_link"); + roi_px_ = nh_priv.param("roi", 128); + roi_rad_ = nh_priv.param("roi_rad", 0.0); + calc_flow_gyro_ = nh_priv.param("calc_flow_gyro", false); img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this); img_pub_ = it_priv.advertise("debug", 1);