gyro_bias_remover.h
Go to the documentation of this file.
1 #pragma once
2 
11 #include <memory>
12 
13 #include <geometry_msgs/Twist.h>
14 #include <geometry_msgs/Vector3Stamped.h>
15 #include <nav_msgs/Odometry.h>
16 #include <ros/console.h>
17 #include <ros/publisher.h>
18 #include <ros/subscriber.h>
19 #include <sensor_msgs/Imu.h>
20 #include <std_msgs/Bool.h>
22 
24 
25 namespace cras
26 {
27 
29 {
31  MOVING,
34 };
35 
37 {
38 protected:
39  void onInit() override;
40 
41  void onImuMsg(const sensor_msgs::ImuConstPtr& msg);
42  void onOdomMsg(const nav_msgs::OdometryConstPtr& msg);
43  void estimateBias(const sensor_msgs::Imu& msg);
44 
46  void reportBiasChange();
47 
48  void speak(const std::string& message, ros::console::levels::Level level);
49 
51  void reset();
52 
53 private:
54  std::unique_ptr<cras::DiagnosedPublisher<sensor_msgs::Imu>> imuPub;
64 
65  geometry_msgs::Vector3Stamped gyroBias;
66  geometry_msgs::Twist stopCommand;
67  std_msgs::Bool stopLockMsg;
68  std_msgs::Bool stopUnlockMsg;
69 
71 
73  size_t minCalibrationSamples {1000};
74  double gyroBiasEstimationRate {0.01};
75  bool skipCalibration {false};
77 
78  double gyroThreshold {0};
79  double cmdVelThreshold {0};
81 
87  bool hasOdomMsg {false};
88 };
89 
90 }
cras::GyroBiasRemoverNodelet::numCalibrationSamples
size_t numCalibrationSamples
Definition: gyro_bias_remover.h:85
cras::GyroBiasRemoverNodelet::reset
void reset()
Definition: gyro_bias_remover.cpp:208
msg
msg
ros::Publisher
cras
cras::GyroBiasRemoverNodelet::stopCommand
geometry_msgs::Twist stopCommand
Definition: gyro_bias_remover.h:66
cras::BiasObserverState::STOPPED_SHORT
@ STOPPED_SHORT
cras::GyroBiasRemoverNodelet::skipCalibration
bool skipCalibration
Definition: gyro_bias_remover.h:75
cras::GyroBiasRemoverNodelet::notMovingDuration
ros::Duration notMovingDuration
Definition: gyro_bias_remover.h:82
cras::GyroBiasRemoverNodelet::stopLockPub
ros::Publisher stopLockPub
Definition: gyro_bias_remover.h:60
cras::BiasObserverState
BiasObserverState
Definition: gyro_bias_remover.h:28
cras::GyroBiasRemoverNodelet::onOdomMsg
void onOdomMsg(const nav_msgs::OdometryConstPtr &msg)
Definition: gyro_bias_remover.cpp:88
cras::GyroBiasRemoverNodelet::produceDiagnostics
void produceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: gyro_bias_remover.cpp:226
cras::BiasObserverState::MOVING
@ MOVING
cras::GyroBiasRemoverNodelet::stopUnlockMsg
std_msgs::Bool stopUnlockMsg
Definition: gyro_bias_remover.h:68
cras::GyroBiasRemoverNodelet::onReset
void onReset(const topic_tools::ShapeShifter &)
Definition: gyro_bias_remover.cpp:221
cras::BiasObserverState::STOPPED_LONG
@ STOPPED_LONG
cras::GyroBiasRemoverNodelet::stopCommandPub
ros::Publisher stopCommandPub
Definition: gyro_bias_remover.h:59
cras::GyroBiasRemoverNodelet::isMovingSub
ros::Subscriber isMovingSub
Definition: gyro_bias_remover.h:62
publisher.h
cras::GyroBiasRemoverNodelet::shouldProduceDiagnostics
bool shouldProduceDiagnostics
Definition: gyro_bias_remover.h:76
cras::GyroBiasRemoverNodelet::lastNotMovingTime
ros::Time lastNotMovingTime
Definition: gyro_bias_remover.h:83
cras::GyroBiasRemoverNodelet::notMovingDurationThreshold
ros::Duration notMovingDurationThreshold
Definition: gyro_bias_remover.h:80
cras::GyroBiasRemoverNodelet::gyroBiasEstimationRate
double gyroBiasEstimationRate
Definition: gyro_bias_remover.h:74
cras::GyroBiasRemoverNodelet::reportBiasChange
void reportBiasChange()
Definition: gyro_bias_remover.cpp:256
console.h
cras::GyroBiasRemoverNodelet
Definition: gyro_bias_remover.h:36
cras::GyroBiasRemoverNodelet::state
BiasObserverState state
Definition: gyro_bias_remover.h:70
cras::GyroBiasRemoverNodelet::speakErrPub
ros::Publisher speakErrPub
Definition: gyro_bias_remover.h:58
subscriber.h
cras::GyroBiasRemoverNodelet::speakWarnPub
ros::Publisher speakWarnPub
Definition: gyro_bias_remover.h:57
cras::GyroBiasRemoverNodelet::calibrationStartedTime
ros::Time calibrationStartedTime
Definition: gyro_bias_remover.h:86
cras::GyroBiasRemoverNodelet::lastReceiveTime
ros::Time lastReceiveTime
Definition: gyro_bias_remover.h:84
cras::GyroBiasRemoverNodelet::imuSub
ros::Subscriber imuSub
Definition: gyro_bias_remover.h:61
cras::GyroBiasRemoverNodelet::stopLockMsg
std_msgs::Bool stopLockMsg
Definition: gyro_bias_remover.h:67
ros::console::levels::Level
Level
cras::GyroBiasRemoverNodelet::onImuMsg
void onImuMsg(const sensor_msgs::ImuConstPtr &msg)
Definition: gyro_bias_remover.cpp:66
cras::GyroBiasRemoverNodelet::imuPub
std::unique_ptr< cras::DiagnosedPublisher< sensor_msgs::Imu > > imuPub
Definition: gyro_bias_remover.h:54
cras::GyroBiasRemoverNodelet::gyroBias
geometry_msgs::Vector3Stamped gyroBias
Definition: gyro_bias_remover.h:65
cras::GyroBiasRemoverNodelet::biasPub
ros::Publisher biasPub
Definition: gyro_bias_remover.h:55
shape_shifter.h
cras::GyroBiasRemoverNodelet::gyroThreshold
double gyroThreshold
Definition: gyro_bias_remover.h:78
cras::BiasObserverState::INITIAL_CALIBRATION
@ INITIAL_CALIBRATION
ros::Time
cras::GyroBiasRemoverNodelet::minCalibrationSamples
size_t minCalibrationSamples
Definition: gyro_bias_remover.h:73
cras::GyroBiasRemoverNodelet::resetSub
ros::Subscriber resetSub
Definition: gyro_bias_remover.h:63
cras::GyroBiasRemoverNodelet::speak
void speak(const std::string &message, ros::console::levels::Level level)
Definition: gyro_bias_remover.cpp:262
cras::GyroBiasRemoverNodelet::hasOdomMsg
bool hasOdomMsg
Definition: gyro_bias_remover.h:87
cras::GyroBiasRemoverNodelet::cmdVelThreshold
double cmdVelThreshold
Definition: gyro_bias_remover.h:79
cras::Nodelet
diagnostic_updater::DiagnosticStatusWrapper
cras::GyroBiasRemoverNodelet::estimateBias
void estimateBias(const sensor_msgs::Imu &msg)
Definition: gyro_bias_remover.cpp:139
cras::GyroBiasRemoverNodelet::onInit
void onInit() override
Definition: gyro_bias_remover.cpp:22
topic_tools::ShapeShifter
ros::Duration
cras::GyroBiasRemoverNodelet::speakInfoPub
ros::Publisher speakInfoPub
Definition: gyro_bias_remover.h:56
cras::GyroBiasRemoverNodelet::initialCalibrationDuration
ros::Duration initialCalibrationDuration
Definition: gyro_bias_remover.h:72
ros::Subscriber
nodelet_utils.hpp


cras_imu_tools
Author(s): Martin Pecka
autogenerated on Fri Jun 23 2023 13:52:51