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
robot_calibration::BaseCalibration::print
std::string print()
Print out current calibration state.
Definition: base_calibration.cpp:77
ros::Publisher
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
robot_calibration::BaseCalibration::imu_subscriber_
ros::Subscriber imu_subscriber_
Definition: base_calibration.h:75
ros.h
robot_calibration::BaseCalibration::printCalibrationData
std::string printCalibrationData()
Print out the calibration data.
Definition: base_calibration.cpp:84
robot_calibration::BaseCalibration::data_mutex_
boost::recursive_mutex data_mutex_
Definition: base_calibration.h:95
robot_calibration::BaseCalibration::cmd_pub_
ros::Publisher cmd_pub_
Definition: base_calibration.h:72
robot_calibration::BaseCalibration::r2_tolerance_
double r2_tolerance_
Definition: base_calibration.h:85
robot_calibration::BaseCalibration::min_angle_
double min_angle_
Definition: base_calibration.h:87
robot_calibration::BaseCalibration
Class for moving the base around and calibrating imu and odometry.
Definition: base_calibration.h:33
robot_calibration::BaseCalibration::ready_
bool ready_
Definition: base_calibration.h:96
robot_calibration::BaseCalibration::align
bool align(double angle, bool verbose=false)
Align to the wall.
Definition: base_calibration.cpp:111
robot_calibration::BaseCalibration::spin
bool spin(double velocity, int rotations, bool verbose=false)
Spin and record imu, odom, scan.
Definition: base_calibration.cpp:157
robot_calibration::BaseCalibration::align_velocity_
double align_velocity_
Definition: base_calibration.h:89
robot_calibration::BaseCalibration::imu_
std::vector< double > imu_
Definition: base_calibration.h:92
robot_calibration::BaseCalibration::sendVelocityCommand
void sendVelocityCommand(double vel)
Send a rotational velocity command.
Definition: base_calibration.cpp:306
robot_calibration::BaseCalibration::last_imu_stamp_
ros::Time last_imu_stamp_
Definition: base_calibration.h:81
robot_calibration::BaseCalibration::odom_angle_
double odom_angle_
Definition: base_calibration.h:79
robot_calibration::BaseCalibration::odom_
std::vector< double > odom_
Definition: base_calibration.h:93
robot_calibration::BaseCalibration::max_angle_
double max_angle_
Definition: base_calibration.h:87
robot_calibration::BaseCalibration::scan_dist_
double scan_dist_
Definition: base_calibration.h:85
robot_calibration::BaseCalibration::scan_subscriber_
ros::Subscriber scan_subscriber_
Definition: base_calibration.h:76
robot_calibration::BaseCalibration::laserCallback
void laserCallback(const sensor_msgs::LaserScan::Ptr &scan)
Definition: base_calibration.cpp:229
robot_calibration::BaseCalibration::imu_angle_
double imu_angle_
Definition: base_calibration.h:82
robot_calibration::BaseCalibration::accel_limit_
double accel_limit_
Definition: base_calibration.h:88
robot_calibration::BaseCalibration::scan_angle_
double scan_angle_
Definition: base_calibration.h:85
robot_calibration::BaseCalibration::imuCallback
void imuCallback(const sensor_msgs::Imu::Ptr &imu)
Definition: base_calibration.cpp:219
robot_calibration::BaseCalibration::BaseCalibration
BaseCalibration(ros::NodeHandle &n)
Create a base calibration instance.
Definition: base_calibration.cpp:36
robot_calibration::BaseCalibration::odom_subscriber_
ros::Subscriber odom_subscriber_
Definition: base_calibration.h:74
robot_calibration::BaseCalibration::odometryCallback
void odometryCallback(const nav_msgs::Odometry::Ptr &odom)
Definition: base_calibration.cpp:209
robot_calibration::BaseCalibration::align_tolerance_
double align_tolerance_
Definition: base_calibration.h:89
robot_calibration::BaseCalibration::scan_
std::vector< double > scan_
Definition: base_calibration.h:91
ros::Time
robot_calibration::BaseCalibration::scan_r2_
double scan_r2_
Definition: base_calibration.h:85
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::BaseCalibration::align_gain_
double align_gain_
Definition: base_calibration.h:89
robot_calibration::BaseCalibration::last_scan_stamp_
ros::Time last_scan_stamp_
Definition: base_calibration.h:84
robot_calibration::BaseCalibration::last_odom_stamp_
ros::Time last_odom_stamp_
Definition: base_calibration.h:78
robot_calibration::BaseCalibration::clearMessages
void clearMessages()
Clear any received messages.
Definition: base_calibration.cpp:70
robot_calibration::BaseCalibration::resetInternal
void resetInternal()
Reset the odom/imu counters.
Definition: base_calibration.cpp:313
ros::NodeHandle
ros::Subscriber
verbose
bool verbose


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01