Program Listing for File socket_can_sender_node.hpp
↰ Return to documentation for file (/tmp/ws/src/ros2_socketcan/ros2_socketcan/include/ros2_socketcan/socket_can_sender_node.hpp
)
// Copyright 2021 the Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.
#ifndef ROS2_SOCKETCAN__SOCKET_CAN_SENDER_NODE_HPP_
#define ROS2_SOCKETCAN__SOCKET_CAN_SENDER_NODE_HPP_
#include <memory>
#include <string>
#include "ros2_socketcan/visibility_control.hpp"
#include "ros2_socketcan/socket_can_sender.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rosidl_runtime_cpp/message_initialization.hpp"
#include "can_msgs/msg/frame.hpp"
#include "ros2_socketcan_msgs/msg/fd_frame.hpp"
#include "lifecycle_msgs/msg/state.hpp"
namespace lc = rclcpp_lifecycle;
using LNI = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface;
namespace drivers
{
namespace socketcan
{
class SOCKETCAN_PUBLIC SocketCanSenderNode final
: public lc::LifecycleNode
{
public:
explicit SocketCanSenderNode(rclcpp::NodeOptions options);
LNI::CallbackReturn on_configure(const lc::State & state) override;
LNI::CallbackReturn on_activate(const lc::State & state) override;
LNI::CallbackReturn on_deactivate(const lc::State & state) override;
LNI::CallbackReturn on_cleanup(const lc::State & state) override;
LNI::CallbackReturn on_shutdown(const lc::State & state) override;
void on_frame(const can_msgs::msg::Frame::SharedPtr msg);
void on_fd_frame(const ros2_socketcan_msgs::msg::FdFrame::SharedPtr msg);
private:
std::string interface_;
bool enable_fd_;
rclcpp::Subscription<can_msgs::msg::Frame>::SharedPtr frames_sub_;
rclcpp::Subscription<ros2_socketcan_msgs::msg::FdFrame>::SharedPtr fd_frames_sub_;
std::unique_ptr<SocketCanSender> sender_;
std::chrono::nanoseconds timeout_ns_;
};
} // namespace socketcan
} // namespace drivers
#endif // ROS2_SOCKETCAN__SOCKET_CAN_SENDER_NODE_HPP_