Common
common packages for kyubic
 
Loading...
Searching...
No Matches
imu_transform_component.hpp
Go to the documentation of this file.
1
10#include <array>
11#include <driver_msgs/msg/imu.hpp>
12#include <localization_msgs/msg/odometry.hpp>
13#include <rclcpp/rclcpp.hpp>
14#include <std_srvs/srv/trigger.hpp>
15
20namespace localization::imu
21{
22
26class IMUTransform : public rclcpp::Node
27{
28private:
29 rclcpp::Publisher<localization_msgs::msg::Odometry>::SharedPtr pub_;
30 rclcpp::Subscription<driver_msgs::msg::IMU>::SharedPtr sub_;
31 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr srv_;
32
33 std::array<double, 3> offset_angle;
34 double roll = 0.0;
35 double pitch = 0.0;
36 double yaw = 0.0;
37
43 void update_callback(const driver_msgs::msg::IMU::UniquePtr msg);
44
49 void reset_callback(
50 const std_srvs::srv::Trigger::Request::SharedPtr request,
51 const std_srvs::srv::Trigger::Response::SharedPtr response);
52
53public:
59 explicit IMUTransform(const rclcpp::NodeOptions & options);
60
64 void reset();
65};
66
67} // namespace localization::imu
IMU transform class.
Definition: imu_transform_component.hpp:27
void reset()
Set offset_angle.
Definition: imu_transform_component.cpp:84
localization