Skip to content

Commit

Permalink
Rename class PublisherWrapper to Publisher
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 18, 2024
1 parent 5f599bb commit 57ea894
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 15 deletions.
18 changes: 9 additions & 9 deletions external/concealer/include/concealer/autoware_universe.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_vehicle_msgs/srv/control_mode_command.hpp>
#include <concealer/continuous_transform_broadcaster.hpp>
#include <concealer/publisher_wrapper.hpp>
#include <concealer/publisher.hpp>
#include <concealer/subscriber_wrapper.hpp>
#include <concealer/visibility.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
Expand Down Expand Up @@ -62,14 +62,14 @@ class AutowareUniverse : public rclcpp::Node,
SubscriberWrapper<TurnIndicatorsCommand> getTurnIndicatorsCommand;
SubscriberWrapper<PathWithLaneId> getPathWithLaneId;

PublisherWrapper<AccelWithCovarianceStamped> setAcceleration;
PublisherWrapper<Odometry> setOdometry;
PublisherWrapper<PoseWithCovarianceStamped> setPose;
PublisherWrapper<SteeringReport> setSteeringReport;
PublisherWrapper<GearReport> setGearReport;
PublisherWrapper<ControlModeReport> setControlModeReport;
PublisherWrapper<VelocityReport> setVelocityReport;
PublisherWrapper<TurnIndicatorsReport> setTurnIndicatorsReport;
Publisher<AccelWithCovarianceStamped> setAcceleration;
Publisher<Odometry> setOdometry;
Publisher<PoseWithCovarianceStamped> setPose;
Publisher<SteeringReport> setSteeringReport;
Publisher<GearReport> setGearReport;
Publisher<ControlModeReport> setControlModeReport;
Publisher<VelocityReport> setVelocityReport;
Publisher<TurnIndicatorsReport> setTurnIndicatorsReport;

std::atomic<geometry_msgs::msg::Accel> current_acceleration;
std::atomic<geometry_msgs::msg::Pose> current_pose;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#include <autoware_vehicle_msgs/msg/turn_indicators_command.hpp>
#include <concealer/autoware_universe.hpp>
#include <concealer/launch.hpp>
#include <concealer/publisher_wrapper.hpp>
#include <concealer/publisher.hpp>
#include <concealer/service_with_validation.hpp>
#include <concealer/subscriber_wrapper.hpp>
#include <concealer/task_queue.hpp>
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__PUBLISHER_WRAPPER_HPP_
#define CONCEALER__PUBLISHER_WRAPPER_HPP_
#ifndef CONCEALER__PUBLISHER_HPP_
#define CONCEALER__PUBLISHER_HPP_

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

namespace concealer
{
template <typename MessageType>
class PublisherWrapper
class Publisher
{
private:
typename rclcpp::Publisher<MessageType>::SharedPtr publisher;
Expand All @@ -33,12 +33,12 @@ class PublisherWrapper
}

template <typename NodeInterface>
explicit PublisherWrapper(std::string topic, NodeInterface & autoware_interface)
explicit Publisher(std::string topic, NodeInterface & autoware_interface)
: publisher(
autoware_interface.template create_publisher<MessageType>(topic, rclcpp::QoS(1).reliable()))
{
}
};
} // namespace concealer

#endif // CONCEALER__PUBLISHER_WRAPPER_HPP_
#endif // CONCEALER__PUBLISHER_HPP_

0 comments on commit 57ea894

Please sign in to comment.