gyro_bias_remover.cpp
Go to the documentation of this file.
1 
9 #include <geometry_msgs/Vector3Stamped.h>
10 #include <nodelet/nodelet.h>
13 #include <std_msgs/String.h>
14 
16 
18 
19 namespace cras
20 {
21 
23 {
24  auto nh = this->getNodeHandle();
25  auto pnh = this->getPrivateNodeHandle();
26  auto params = this->privateParams();
27 
28  this->initialCalibrationDuration = params->getParam("initial_calibration_duration", ros::Duration(15), "s");
29  this->minCalibrationSamples = params->getParam("min_calibration_samples", 1000_sz, "IMU samples");
30  this->gyroBiasEstimationRate = params->getParam("bias_estimation_rate", 0.01);
31  this->gyroThreshold = params->getParam("gyro_not_moving_threshold", 0.05, "rad/s");
32  this->cmdVelThreshold = params->getParam("cmd_vel_threshold", 1e-3, "m/s or rad/s");
33  this->notMovingDurationThreshold = params->getParam("not_moving_duration_threshold", ros::Duration(2), "s");
34  this->skipCalibration = params->getParam("skip_calibration", false);
35  this->shouldProduceDiagnostics = params->getParam("produce_diagnostics", true);
36 
37  if (this->skipCalibration)
39 
41  this->stopLockMsg.data = true;
42  this->stopUnlockMsg.data = false;
43 
44  this->imuPub = this->advertiseDiagnosed<sensor_msgs::Imu>(nh, pnh, "output", "imu_unbiased/data", 100);
45  this->biasPub = nh.advertise<geometry_msgs::Vector3Stamped>("imu/gyro_bias", 100, true);
46  this->speakInfoPub = nh.advertise<std_msgs::String>("speak/info", 2);
47  this->speakWarnPub = nh.advertise<std_msgs::String>("speak/warn", 2);
48  this->speakErrPub = nh.advertise<std_msgs::String>("speak/err", 2);
49  this->stopCommandPub = nh.advertise<geometry_msgs::Twist>("emergency_stop/cmd_vel", 2);
50  this->stopLockPub = nh.advertise<std_msgs::Bool>("emergency_stop", 2);
51 
52  this->imuSub = nh.subscribe("imu/data", 100, &GyroBiasRemoverNodelet::onImuMsg, this);
53  this->isMovingSub = nh.subscribe("odom_cmd_vel", 100, &GyroBiasRemoverNodelet::onOdomMsg, this);
54  this->resetSub = nh.subscribe("reset", 1, &GyroBiasRemoverNodelet::onReset, this);
55 
56  if (this->shouldProduceDiagnostics)
57  {
59  this->startDiagTimer();
60  }
61 
62  CRAS_INFO("IMU calibration has started.");
63  this->speak("Calibrating gyro, do not move me.", ros::console::levels::Warn);
64 }
65 
66 void GyroBiasRemoverNodelet::onImuMsg(const sensor_msgs::ImuConstPtr& msg)
67 {
68  if (ros::Time::now() + ros::Duration(3) < this->lastReceiveTime)
69  {
70  CRAS_WARN("ROS time has jumped back, resetting.");
71  this->reset();
72  }
74 
75  this->estimateBias(*msg);
76 
78  return;
79 
80  sensor_msgs::Imu unbiased = *msg;
81  unbiased.angular_velocity.x -= this->gyroBias.vector.x;
82  unbiased.angular_velocity.y -= this->gyroBias.vector.y;
83  unbiased.angular_velocity.z -= this->gyroBias.vector.z;
84 
85  this->imuPub->publish(unbiased);
86 }
87 
88 void GyroBiasRemoverNodelet::onOdomMsg(const nav_msgs::OdometryConstPtr& msg)
89 {
90  this->hasOdomMsg = true;
91  CRAS_DEBUG_THROTTLE(1.0, "State is %i", static_cast<std::underlying_type<BiasObserverState>::type>(this->state));
92 
93  const auto& v = msg->twist.twist.linear;
94  const auto& w = msg->twist.twist.angular;
95 
96  const auto& th = this->cmdVelThreshold;
97 
98  const auto isNowMoving = std::abs(v.x) > th || std::abs(v.y) > th || std::abs(v.z) > th || std::abs(w.x) > th
99  || std::abs(w.y) > th || std::abs(w.z) > th;
100 
101  if (isNowMoving && this->state == BiasObserverState::INITIAL_CALIBRATION)
102  {
103  CRAS_ERROR("Robot has moved during IMU calibration!");
104  this->speak("Gyro calibration failed, I moved!", ros::console::levels::Error);
105  }
106 
107  if (isNowMoving)
108  {
110  {
112  this->reportBiasChange();
114  }
115  this->notMovingDuration = {0, 0};
116  this->lastNotMovingTime = {0, 0};
117  return;
118  }
119 
120  if (this->state == BiasObserverState::MOVING)
121  {
123  this->lastNotMovingTime = msg->header.stamp;
124  this->notMovingDuration = {0, 0};
125  return;
126  }
127 
128  this->notMovingDuration += msg->header.stamp - this->lastNotMovingTime;
129  this->lastNotMovingTime = msg->header.stamp;
131  {
134  else
136  }
137 }
138 
139 void GyroBiasRemoverNodelet::estimateBias(const sensor_msgs::Imu& msg)
140 {
142  return;
143 
144  const auto& w = msg.angular_velocity;
145  auto& bias = this->gyroBias.vector;
146 
148  {
149  bias.x += w.x;
150  bias.y += w.y;
151  bias.z += w.z;
152  this->numCalibrationSamples++;
153 
154  const auto calibDuration = msg.header.stamp - this->calibrationStartedTime;
155  if (this->numCalibrationSamples >= this->minCalibrationSamples && calibDuration >= this->initialCalibrationDuration)
156  {
157  bias.x /= static_cast<double>(this->numCalibrationSamples);
158  bias.y /= static_cast<double>(this->numCalibrationSamples);
159  bias.z /= static_cast<double>(this->numCalibrationSamples);
160 
161  this->gyroBias.header = msg.header;
162  this->biasPub.publish(this->gyroBias);
163 
164  if (this->lastNotMovingTime == ros::Time(0, 0))
166  else if (this->notMovingDuration >= this->notMovingDurationThreshold)
168  else
170  CRAS_WARN("IMU calibration finished.");
171  this->speak("Gyros calibrated!", ros::console::levels::Warn);
172  this->stopLockPub.publish(this->stopUnlockMsg);
173  this->reportBiasChange();
174  }
175  else
176  {
177  CRAS_WARN_THROTTLE(1.0, "IMU is calibrating, do not move the robot.");
178  this->stopCommandPub.publish(this->stopCommand);
179  this->stopLockPub.publish(this->stopLockMsg);
180  }
181  }
182  else
183  {
184  auto th = this->gyroThreshold;
185 
186  if (std::abs(w.x - bias.x) > th || std::abs(w.y - bias.y) > th || std::abs(w.z - bias.z) > th)
187  {
189  this->lastNotMovingTime = {0, 0};
190  this->notMovingDuration = {0, 0};
191  this->reportBiasChange();
192  return;
193  }
194 
195  const auto& rate = this->gyroBiasEstimationRate;
196 
197  bias.x = (1 - rate) * bias.x + rate * w.x;
198  bias.y = (1 - rate) * bias.y + rate * w.y;
199  bias.z = (1 - rate) * bias.z + rate * w.z;
200 
201  this->gyroBias.header.frame_id = msg.header.frame_id;
202  this->gyroBias.header.stamp = msg.header.stamp;
203 
204  this->biasPub.publish(this->gyroBias);
205  }
206 }
207 
209 {
211  this->numCalibrationSamples = 0;
212  this->gyroBias.vector.x = this->gyroBias.vector.y = this->gyroBias.vector.z = 0;
213  this->notMovingDuration = {0, 0};
214  this->lastNotMovingTime = {0, 0};
216  this->hasOdomMsg = false;
217  if (this->shouldProduceDiagnostics)
218  this->getDiagUpdater().force_update();
219 }
220 
222 {
223  this->reset();
224 }
225 
227 {
229  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Initial calibration");
230  else if (this->hasOdomMsg)
231  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Running");
232  else
233  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No odom messages received");
234 
235  switch (this->state)
236  {
238  stat.add("State", "Initial calibration");
239  stat.addf("Num samples", "%lu", this->numCalibrationSamples);
240  stat.add("Duration of calibration", cras::to_string(ros::Time::now() - this->calibrationStartedTime));
241  break;
243  stat.add("State", "Moving");
244  break;
246  stat.add("State", "Just stopped");
247  stat.add("Last motion before", cras::to_string(this->notMovingDuration));
248  break;
250  stat.add("State", "Standing still, calibrating bias");
251  stat.add("Last motion before", cras::to_string(this->notMovingDuration));
252  break;
253  }
254 }
255 
257 {
258  CRAS_INFO("Estimated gyro bias is: x=%.6f y=%.6f z=%.6f",
259  this->gyroBias.vector.x, this->gyroBias.vector.y, this->gyroBias.vector.z);
260 }
261 
262 void GyroBiasRemoverNodelet::speak(const std::string& message, const ros::console::levels::Level level)
263 {
264  std_msgs::String msg;
265  msg.data = message;
266 
267  switch (level)
268  {
270  this->speakInfoPub.publish(msg);
271  break;
273  this->speakWarnPub.publish(msg);
274  break;
275  default:
276  this->speakErrPub.publish(msg);
277  break;
278  }
279 }
280 
281 }
282 
cras::GyroBiasRemoverNodelet::numCalibrationSamples
size_t numCalibrationSamples
Definition: gyro_bias_remover.h:85
cras::GyroBiasRemoverNodelet::reset
void reset()
Definition: gyro_bias_remover.cpp:208
ros::console::levels::Error
Error
msg
msg
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
cras
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
diagnostic_updater::Updater::force_update
void force_update()
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
NodeletParamHelper< ::nodelet::Nodelet >::privateParams
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
cras::GyroBiasRemoverNodelet::notMovingDuration
ros::Duration notMovingDuration
Definition: gyro_bias_remover.h:82
cras::GyroBiasRemoverNodelet::stopLockPub
ros::Publisher stopLockPub
Definition: gyro_bias_remover.h:60
NodeletWithDiagnostics< ::nodelet::Nodelet >::getDiagUpdater
::cras::DiagnosticUpdater & getDiagUpdater(bool forceNew=false) const
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_WARN
#define CRAS_WARN(...)
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_ERROR
#define CRAS_ERROR(...)
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
cras::GyroBiasRemoverNodelet::isMovingSub
ros::Subscriber isMovingSub
Definition: gyro_bias_remover.h:62
cras::GyroBiasRemoverNodelet::shouldProduceDiagnostics
bool shouldProduceDiagnostics
Definition: gyro_bias_remover.h:76
gyro_bias_remover.h
cras::GyroBiasRemoverNodelet::lastNotMovingTime
ros::Time lastNotMovingTime
Definition: gyro_bias_remover.h:83
CRAS_INFO
#define CRAS_INFO(...)
cras::GyroBiasRemoverNodelet::notMovingDurationThreshold
ros::Duration notMovingDurationThreshold
Definition: gyro_bias_remover.h:80
cras::GyroBiasRemoverNodelet::gyroBiasEstimationRate
double gyroBiasEstimationRate
Definition: gyro_bias_remover.h:74
literal_sz.h
class_list_macros.h
cras::GyroBiasRemoverNodelet::reportBiasChange
void reportBiasChange()
Definition: gyro_bias_remover.cpp:256
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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
CRAS_DEBUG_THROTTLE
#define CRAS_DEBUG_THROTTLE(period,...)
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
ros::console::levels::Info
Info
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
nodelet::Nodelet
CRAS_WARN_THROTTLE
#define CRAS_WARN_THROTTLE(period,...)
ros::Time
NodeletParamHelper< ::nodelet::Nodelet >::params
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
cras::GyroBiasRemoverNodelet::minCalibrationSamples
size_t minCalibrationSamples
Definition: gyro_bias_remover.h:73
NodeletWithDiagnostics< ::nodelet::Nodelet >::startDiagTimer
void startDiagTimer() const
nodelet.h
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
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
cras::GyroBiasRemoverNodelet::hasOdomMsg
bool hasOdomMsg
Definition: gyro_bias_remover.h:87
cras::GyroBiasRemoverNodelet::cmdVelThreshold
double cmdVelThreshold
Definition: gyro_bias_remover.h:79
diagnostic_updater::DiagnosticStatusWrapper
ros::console::levels::Warn
Warn
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
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
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
cras::to_string
inline ::std::string to_string(char *value)
ros::Time::now
static Time now()


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