15#ifndef ROBOLIGO_COMMON_CONNECTOR_SENSORS__IMU_HPP_
16#define ROBOLIGO_COMMON_CONNECTOR_SENSORS__IMU_HPP_
18#include <sensor_msgs/msg/imu.hpp>
39 Imu(std::string new_name, std::string new_topic)
40 :
Sensor(new_name, new_topic){}
46 rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr
subscriber;
48 sensor_msgs::msg::Imu::SharedPtr
data;
53 void callback(sensor_msgs::msg::Imu::SharedPtr msg);
Imu(std::string new_name, std::string new_topic)
Constructor for Imu sensor.
Definition Imu.hpp:39
sensor_msgs::msg::Imu::SharedPtr data
Latest IMU data received from the subscriber.
Definition Imu.hpp:48
void callback(sensor_msgs::msg::Imu::SharedPtr msg)
Callback function triggered when new IMU message is received.
Definition Imu.cpp:20
rclcpp::Subscription< sensor_msgs::msg::Imu >::SharedPtr subscriber
ROS 2 subscription handle for IMU messages.
Definition Imu.hpp:46
virtual ~Imu()=default
Virtual destructor.
Sensor(std::string new_name, std::string new_topic)
Constructor for Sensor.
Definition Sensor.cpp:19
Definition ClassificationBase.hpp:28