Skip to content

Commit

Permalink
Rename class SubscriberWrapper to Subscriber
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Dec 19, 2024
1 parent f601263 commit 5ac238a
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 21 deletions.
10 changes: 5 additions & 5 deletions external/concealer/include/concealer/autoware_universe.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include <autoware_vehicle_msgs/srv/control_mode_command.hpp>
#include <concealer/continuous_transform_broadcaster.hpp>
#include <concealer/publisher.hpp>
#include <concealer/subscriber_wrapper.hpp>
#include <concealer/subscriber.hpp>
#include <concealer/visibility.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
Expand Down Expand Up @@ -57,10 +57,10 @@ class AutowareUniverse : public rclcpp::Node,
using TurnIndicatorsReport = autoware_vehicle_msgs::msg::TurnIndicatorsReport;
using VelocityReport = autoware_vehicle_msgs::msg::VelocityReport;

SubscriberWrapper<Control> getCommand;
SubscriberWrapper<GearCommand> getGearCommand;
SubscriberWrapper<TurnIndicatorsCommand> getTurnIndicatorsCommand;
SubscriberWrapper<PathWithLaneId> getPathWithLaneId;
Subscriber<Control> getCommand;
Subscriber<GearCommand> getGearCommand;
Subscriber<TurnIndicatorsCommand> getTurnIndicatorsCommand;
Subscriber<PathWithLaneId> getPathWithLaneId;

Publisher<AccelWithCovarianceStamped> setAcceleration;
Publisher<Odometry> setOdometry;
Expand Down
20 changes: 10 additions & 10 deletions external/concealer/include/concealer/field_operator_application.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include <concealer/launch.hpp>
#include <concealer/publisher.hpp>
#include <concealer/service_with_validation.hpp>
#include <concealer/subscriber_wrapper.hpp>
#include <concealer/subscriber.hpp>
#include <concealer/task_queue.hpp>
#include <concealer/transition_assertion.hpp>
#include <concealer/visibility.hpp>
Expand Down Expand Up @@ -107,17 +107,17 @@ struct FieldOperatorApplication : public rclcpp::Node,
using SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit;
using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode;

SubscriberWrapper<AutowareState> getAutowareState;
SubscriberWrapper<Control> getCommand;
SubscriberWrapper<CooperateStatusArray> getCooperateStatusArray;
SubscriberWrapper<Emergency> getEmergencyState;
Subscriber<AutowareState> getAutowareState;
Subscriber<Control> getCommand;
Subscriber<CooperateStatusArray> getCooperateStatusArray;
Subscriber<Emergency> getEmergencyState;
#if __has_include(<autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>)
SubscriberWrapper<LocalizationInitializationState> getLocalizationState;
Subscriber<LocalizationInitializationState> getLocalizationState;
#endif
SubscriberWrapper<MrmState> getMrmState;
SubscriberWrapper<PathWithLaneId> getPathWithLaneId;
SubscriberWrapper<Trajectory> getTrajectory;
SubscriberWrapper<TurnIndicatorsCommand> getTurnIndicatorsCommand;
Subscriber<MrmState> getMrmState;
Subscriber<PathWithLaneId> getPathWithLaneId;
Subscriber<Trajectory> getTrajectory;
Subscriber<TurnIndicatorsCommand> getTurnIndicatorsCommand;

ServiceWithValidation<ClearRoute> requestClearRoute;
ServiceWithValidation<CooperateCommands> requestCooperateCommands;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef CONCEALER__SUBSCRIBER_WRAPPER_HPP_
#define CONCEALER__SUBSCRIBER_WRAPPER_HPP_
#ifndef CONCEALER__SUBSCRIBER_HPP_
#define CONCEALER__SUBSCRIBER_HPP_

#include <memory>
#include <rclcpp/rclcpp.hpp>

namespace concealer
{
template <typename Message>
class SubscriberWrapper
class Subscriber
{
typename Message::ConstSharedPtr current_value = std::make_shared<const Message>();

Expand All @@ -31,7 +31,7 @@ class SubscriberWrapper
auto operator()() const -> const auto & { return *std::atomic_load(&current_value); }

template <typename Autoware, typename Callback>
explicit SubscriberWrapper(
explicit Subscriber(
const std::string & topic, const rclcpp::QoS & quality_of_service, Autoware & autoware,
const Callback & callback)
: subscription(autoware.template create_subscription<Message>(
Expand All @@ -45,7 +45,7 @@ class SubscriberWrapper
}

template <typename Autoware>
explicit SubscriberWrapper(
explicit Subscriber(
const std::string & topic, const rclcpp::QoS & quality_of_service, Autoware & autoware)
: subscription(autoware.template create_subscription<Message>(
topic, quality_of_service, [this](const typename Message::ConstSharedPtr & message) {
Expand All @@ -56,4 +56,4 @@ class SubscriberWrapper
};
} // namespace concealer

#endif // CONCEALER__SUBSCRIBER_WRAPPER_HPP_
#endif // CONCEALER__SUBSCRIBER_HPP_

0 comments on commit 5ac238a

Please sign in to comment.