Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
node.hpp
Go to the documentation of this file.
1#pragma once
2
3#include "config/parameters.hpp"
4#include "custom_interfaces/msg/velocities.hpp"
6#include "estimators/map.hpp"
7#include "rclcpp/rclcpp.hpp"
16class VENode : public rclcpp::Node {
17protected:
19 std::shared_ptr<VelocityEstimator> _velocity_estimator_;
20 rclcpp::Publisher<custom_interfaces::msg::Velocities>::SharedPtr _velocities_pub_;
21 void publish_velocities() const;
22
23public:
24 VENode(const VEParameters& parameters);
25};
Node class for the velocity estimation node.
Definition node.hpp:16
void publish_velocities() const
Definition node.cpp:10
rclcpp::Publisher< custom_interfaces::msg::Velocities >::SharedPtr _velocities_pub_
Definition node.hpp:20
VEParameters _parameters_
Definition node.hpp:18
std::shared_ptr< VelocityEstimator > _velocity_estimator_
Definition node.hpp:19