Go to the documentation of this file.
9 #include <geometry_msgs/Vector3Stamped.h>
13 #include <std_msgs/String.h>
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);
62 CRAS_INFO(
"IMU calibration has started.");
70 CRAS_WARN(
"ROS time has jumped back, resetting.");
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;
85 this->
imuPub->publish(unbiased);
93 const auto& v =
msg->twist.twist.linear;
94 const auto& w =
msg->twist.twist.angular;
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;
103 CRAS_ERROR(
"Robot has moved during IMU calibration!");
144 const auto& w =
msg.angular_velocity;
186 if (std::abs(w.x - bias.x) > th || std::abs(w.y - bias.y) > th || std::abs(w.z - bias.z) > th)
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;
201 this->gyroBias.header.frame_id =
msg.header.frame_id;
202 this->gyroBias.header.stamp =
msg.header.stamp;
204 this->biasPub.publish(this->gyroBias);
229 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Initial calibration");
231 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Running");
233 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"No odom messages received");
238 stat.
add(
"State",
"Initial calibration");
243 stat.
add(
"State",
"Moving");
246 stat.
add(
"State",
"Just stopped");
250 stat.
add(
"State",
"Standing still, calibrating bias");
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);
264 std_msgs::String
msg;
size_t numCalibrationSamples
ros::NodeHandle & getNodeHandle() const
void add(const std::string &key, const bool &b)
geometry_msgs::Twist stopCommand
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
ros::Duration notMovingDuration
ros::Publisher stopLockPub
::cras::DiagnosticUpdater & getDiagUpdater(bool forceNew=false) const
void onOdomMsg(const nav_msgs::OdometryConstPtr &msg)
void produceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
std_msgs::Bool stopUnlockMsg
void onReset(const topic_tools::ShapeShifter &)
ros::Publisher stopCommandPub
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber isMovingSub
bool shouldProduceDiagnostics
ros::Time lastNotMovingTime
ros::Duration notMovingDurationThreshold
double gyroBiasEstimationRate
void summary(const diagnostic_msgs::DiagnosticStatus &src)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Publisher speakErrPub
#define CRAS_DEBUG_THROTTLE(period,...)
ros::Publisher speakWarnPub
ros::Time calibrationStartedTime
ros::Time lastReceiveTime
std_msgs::Bool stopLockMsg
void onImuMsg(const sensor_msgs::ImuConstPtr &msg)
std::unique_ptr< cras::DiagnosedPublisher< sensor_msgs::Imu > > imuPub
geometry_msgs::Vector3Stamped gyroBias
#define CRAS_WARN_THROTTLE(period,...)
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
size_t minCalibrationSamples
void startDiagTimer() const
void speak(const std::string &message, ros::console::levels::Level level)
void addf(const std::string &key, const char *format,...)
void estimateBias(const sensor_msgs::Imu &msg)
void add(const std::string &name, TaskFunction f)
ros::Publisher speakInfoPub
ros::Duration initialCalibrationDuration
inline ::std::string to_string(char *value)
cras_imu_tools
Author(s): Martin Pecka
autogenerated on Fri Jun 23 2023 13:52:51