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

Rolling #29

Closed
wants to merge 4 commits into from
Closed
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
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <geometry_msgs/msg/pose.hpp>

#include <boost/optional.hpp>
#include <boost/optional/optional_io.hpp>

#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ template <typename T>
class LowpassFilterInterface
{
protected:
boost::optional<T> x_; //!< @brief current filtered value
std::optional<T> x_; //!< @brief current filtered value
double gain_; //!< @brief gain value of first-order low-pass filter

public:
Expand All @@ -36,7 +36,7 @@ class LowpassFilterInterface
void reset() { x_ = {}; }
void reset(const T & x) { x_ = x; }

boost::optional<T> getValue() const { return x_; }
std::optional<T> getValue() const { return x_; }

virtual T filter(const T & u) = 0;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@
#ifndef SIGNAL_PROCESSING__LOWPASS_FILTER_1D_HPP_
#define SIGNAL_PROCESSING__LOWPASS_FILTER_1D_HPP_

#include <boost/optional.hpp>
// #include <boost/optional/optional_io.hpp>
#include <optional>

namespace signal_processing
{
Expand All @@ -29,7 +30,7 @@ double lowpassFilter(const double current_val, const double prev_val, const doub
class LowpassFilter1d
{
private:
boost::optional<double> x_; //!< @brief current filtered value
std::optional<double> x_; //!< @brief current filtered value
double gain_; //!< @brief gain value of first-order low-pass filter

public:
Expand All @@ -38,7 +39,7 @@ class LowpassFilter1d
void reset();
void reset(const double x);

boost::optional<double> getValue() const;
std::optional<double> getValue() const;
double filter(const double u);
};

Expand Down
4 changes: 2 additions & 2 deletions common/signal_processing/src/lowpass_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ geometry_msgs::msg::Twist LowpassFilterTwist::filter(const geometry_msgs::msg::T
x_->angular.y = gain_ * x_->angular.y + (1.0 - gain_) * u.angular.y;
x_->angular.z = gain_ * x_->angular.z + (1.0 - gain_) * u.angular.z;

return x_.get();
return x_.value();
}

x_ = u;
return x_.get();
return x_.value();
}
10 changes: 5 additions & 5 deletions common/signal_processing/src/lowpass_filter_1d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,27 +28,27 @@ LowpassFilter1d::LowpassFilter1d(const double gain) : gain_(gain)

void LowpassFilter1d::reset()
{
x_ = {};
x_ = std::nullopt;
}

void LowpassFilter1d::reset(const double x)
{
x_ = x;
}

boost::optional<double> LowpassFilter1d::getValue() const
std::optional<double> LowpassFilter1d::getValue() const
{
return x_;
}

double LowpassFilter1d::filter(const double u)
{
if (x_) {
const double ret = gain_ * x_.get() + (1.0 - gain_) * u;
const double ret = gain_ * x_.value() + (1.0 - gain_) * u;
x_ = ret;
return x_.get();
return x_.value();
}

x_ = u;
return x_.get();
return x_.value();
}
4 changes: 2 additions & 2 deletions common/signal_processing/test/src/lowpass_filter_1d_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ TEST(lowpass_filter_1d, filter)
LowpassFilter1d lowpass_filter_1d(0.1);

// initial state
EXPECT_EQ(lowpass_filter_1d.getValue(), boost::none);
EXPECT_EQ(lowpass_filter_1d.getValue(), std::nullopt);

// random filter
EXPECT_NEAR(lowpass_filter_1d.filter(0.0), 0.0, epsilon);
Expand All @@ -33,7 +33,7 @@ TEST(lowpass_filter_1d, filter)

// reset without value
lowpass_filter_1d.reset();
EXPECT_EQ(lowpass_filter_1d.getValue(), boost::none);
EXPECT_EQ(lowpass_filter_1d.getValue(), std::nullopt);

// reset with value
lowpass_filter_1d.reset(-1.1);
Expand Down
4 changes: 2 additions & 2 deletions common/signal_processing/test/src/lowpass_filter_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ TEST(lowpass_filter_twist, filter)
LowpassFilterTwist lowpass_filter_(0.1);

{ // initial state
EXPECT_EQ(lowpass_filter_.getValue(), boost::none);
EXPECT_EQ(lowpass_filter_.getValue(), std::nullopt);
}

{ // random filter
Expand All @@ -56,7 +56,7 @@ TEST(lowpass_filter_twist, filter)

{ // reset without value
lowpass_filter_.reset();
EXPECT_EQ(lowpass_filter_.getValue(), boost::none);
EXPECT_EQ(lowpass_filter_.getValue(), std::nullopt);
}

{ // reset with value
Expand Down
2 changes: 1 addition & 1 deletion localization/yabloc/yabloc_common/src/cv_decompress.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <opencv4/opencv2/imgcodecs.hpp>
#include <opencv4/opencv2/imgproc.hpp>

#include <cv_bridge/cv_bridge.h>
#include <cv_bridge/cv_bridge.hpp>

#include <iostream>

Expand Down
2 changes: 1 addition & 1 deletion localization/yabloc/yabloc_common/src/pub_sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "yabloc_common/pub_sub.hpp"

#include <cv_bridge/cv_bridge.h>
#include <cv_bridge/cv_bridge.hpp>
#include <pcl_conversions/pcl_conversions.h>

namespace yabloc::common
Expand Down
4 changes: 2 additions & 2 deletions planning/rtc_interface/src/rtc_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,10 +105,10 @@ RTCInterface::RTCInterface(rclcpp::Node * node, const std::string & name, const
srv_commands_ = node->create_service<CooperateCommands>(
cooperate_commands_namespace_ + "/" + name,
std::bind(&RTCInterface::onCooperateCommandService, this, _1, _2),
rmw_qos_profile_services_default, callback_group_);
rclcpp::QoS(rclcpp::ServicesQoS()), callback_group_);
srv_auto_mode_ = node->create_service<AutoMode>(
enable_auto_mode_namespace_ + "/" + name,
std::bind(&RTCInterface::onAutoModeService, this, _1, _2), rmw_qos_profile_services_default,
std::bind(&RTCInterface::onAutoModeService, this, _1, _2), rclcpp::QoS(rclcpp::ServicesQoS()),
callback_group_);

// Module
Expand Down
Loading