Skip to content

Commit

Permalink
fix: change type for epsilon (#822)
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <daisuke.nishimatsu1021@gmail.com>
  • Loading branch information
wep21 committed Jan 17, 2024
1 parent 8e2c0c5 commit 24dec52
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
// Declare/read parameters
int queue_size = this->declare_parameter("queue_size", 5);
bool approx = this->declare_parameter("approximate_sync", false);
bool approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
double approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
this->declare_parameter("use_system_default_qos", false);

// Synchronize callbacks
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
// Declare/read parameters
int queue_size = this->declare_parameter("queue_size", 5);
bool approx = this->declare_parameter("approximate_sync", false);
bool approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
double approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
this->declare_parameter("use_system_default_qos", false);
rcl_interfaces::msg::ParameterDescriptor descriptor;
// TODO(ivanpauno): Confirm if using point cloud padding in `sensor_msgs::msg::PointCloud2`
Expand Down

0 comments on commit 24dec52

Please sign in to comment.