rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
imu_filter_base.h
Go to the documentation of this file.
1//
2// Created by yezi on 2022/3/26.
3//
4
5#pragma once
6
7#include <ros/ros.h>
8#include <sensor_msgs/Imu.h>
9#include <sensor_msgs/Temperature.h>
10#include <sensor_msgs/TimeReference.h>
11#include <realtime_tools/realtime_publisher.h>
12
13namespace rm_common
14{
16{
17public:
18 bool init(XmlRpc::XmlRpcValue& imu_data, const std::string& name);
19 void update(ros::Time time, double* accel, double* omega, double* ori, double* accel_cov, double* omega_cov,
20 double* ori_cov, double temp, bool camera_trigger);
21 virtual void getOrientation(double& q0, double& q1, double& q2, double& q3) = 0;
22
23protected:
24 virtual bool initFilter(XmlRpc::XmlRpcValue& imu_data) = 0;
25 virtual void resetFilter() = 0;
26 virtual void filterUpdate(double ax, double ay, double az, double wx, double wy, double wz, double dt) = 0;
27 ros::Time last_update_;
28 bool initialized_filter_{ false };
29 std::string frame_id_;
30 ros::Publisher imu_data_pub_;
31 ros::Publisher imu_temp_pub_;
32 ros::Publisher trigger_time_pub_;
33 sensor_msgs::Imu imu_pub_data_;
34 sensor_msgs::Temperature temp_pub_data_;
35 sensor_msgs::TimeReference trigger_time_pub_data_;
36};
37} // namespace rm_common
Definition imu_filter_base.h:16
virtual void getOrientation(double &q0, double &q1, double &q2, double &q3)=0
sensor_msgs::Temperature temp_pub_data_
Definition imu_filter_base.h:34
ros::Publisher imu_temp_pub_
Definition imu_filter_base.h:31
std::string frame_id_
Definition imu_filter_base.h:29
virtual void resetFilter()=0
sensor_msgs::TimeReference trigger_time_pub_data_
Definition imu_filter_base.h:35
virtual bool initFilter(XmlRpc::XmlRpcValue &imu_data)=0
ros::Publisher trigger_time_pub_
Definition imu_filter_base.h:32
bool init(XmlRpc::XmlRpcValue &imu_data, const std::string &name)
Definition imu_filter_base.cpp:9
ros::Publisher imu_data_pub_
Definition imu_filter_base.h:30
sensor_msgs::Imu imu_pub_data_
Definition imu_filter_base.h:33
bool initialized_filter_
Definition imu_filter_base.h:28
virtual void filterUpdate(double ax, double ay, double az, double wx, double wy, double wz, double dt)=0
void update(ros::Time time, double *accel, double *omega, double *ori, double *accel_cov, double *omega_cov, double *ori_cov, double temp, bool camera_trigger)
Definition imu_filter_base.cpp:20
ros::Time last_update_
Definition imu_filter_base.h:27
Definition calibration_queue.h:44