21 #include <boost/thread/recursive_mutex.hpp> 24 #include <sensor_msgs/Imu.h> 25 #include <sensor_msgs/LaserScan.h> 26 #include <nav_msgs/Odometry.h> 56 bool align(
double angle,
bool verbose =
false);
59 bool spin(
double velocity,
int rotations,
bool verbose =
false);
ros::Subscriber odom_subscriber_
void odometryCallback(const nav_msgs::Odometry::Ptr &odom)
boost::recursive_mutex data_mutex_
BaseCalibration(ros::NodeHandle &n)
Create a base calibration instance.
std::vector< double > odom_
void sendVelocityCommand(double vel)
Send a rotational velocity command.
std::string print()
Print out current calibration state.
void imuCallback(const sensor_msgs::Imu::Ptr &imu)
ros::Time last_imu_stamp_
ros::Subscriber imu_subscriber_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void resetInternal()
Reset the odom/imu counters.
std::vector< double > scan_
bool align(double angle, bool verbose=false)
Align to the wall.
ros::Time last_scan_stamp_
bool spin(double velocity, int rotations, bool verbose=false)
Spin and record imu, odom, scan.
Calibration code lives under this namespace.
ros::Time last_odom_stamp_
Class for moving the base around and calibrating imu and odometry.
std::vector< double > imu_
void laserCallback(const sensor_msgs::LaserScan::Ptr &scan)
void clearMessages()
Clear any received messages.
ros::Subscriber scan_subscriber_
std::string printCalibrationData()
Print out the calibration data.