base_calibration.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2022 Michael Ferguson
3  * Copyright (C) 2015 Fetch Robotics Inc.
4  * Copyright (C) 2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Michael Ferguson
20 
21 #include <boost/thread/recursive_mutex.hpp>
22 
23 #include <ros/ros.h>
24 #include <sensor_msgs/Imu.h>
25 #include <sensor_msgs/LaserScan.h>
26 #include <nav_msgs/Odometry.h>
27 
29 {
34 {
35 public:
41 
43  void clearMessages();
44 
46  std::string print();
47 
49  std::string printCalibrationData();
50 
56  bool align(double angle, bool verbose = false);
57 
59  bool spin(double velocity, int rotations, bool verbose = false);
60 
61 private:
62  void odometryCallback(const nav_msgs::Odometry::Ptr& odom);
63  void imuCallback(const sensor_msgs::Imu::Ptr& imu);
64  void laserCallback(const sensor_msgs::LaserScan::Ptr& scan);
65 
67  void sendVelocityCommand(double vel);
68 
70  void resetInternal();
71 
73 
77 
79  double odom_angle_;
80 
82  double imu_angle_;
83 
86 
88  double accel_limit_;
90 
91  std::vector<double> scan_;
92  std::vector<double> imu_;
93  std::vector<double> odom_;
94 
95  boost::recursive_mutex data_mutex_;
96  bool ready_;
97 };
98 
99 } // namespace robot_calibration
void odometryCallback(const nav_msgs::Odometry::Ptr &odom)
boost::recursive_mutex data_mutex_
BaseCalibration(ros::NodeHandle &n)
Create a base calibration instance.
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)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void resetInternal()
Reset the odom/imu counters.
bool align(double angle, bool verbose=false)
Align to the wall.
bool spin(double velocity, int rotations, bool verbose=false)
Spin and record imu, odom, scan.
Calibration code lives under this namespace.
Class for moving the base around and calibrating imu and odometry.
void laserCallback(const sensor_msgs::LaserScan::Ptr &scan)
void clearMessages()
Clear any received messages.
std::string printCalibrationData()
Print out the calibration data.


robot_calibration
Author(s): Michael Ferguson
autogenerated on Wed May 24 2023 02:30:23