base_calibration.cpp
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 <cmath>
22 #include <fstream>
23 #include <boost/thread/recursive_mutex.hpp>
24 
25 #include <ros/ros.h>
26 #include <geometry_msgs/Twist.h>
27 #include <sensor_msgs/Imu.h>
28 #include <sensor_msgs/LaserScan.h>
29 #include <nav_msgs/Odometry.h>
31 
32 #define PI 3.14159265359
33 
34 namespace robot_calibration
35 {
37 {
38  // Setup times
40 
41  // Get params
42  ros::NodeHandle nh("~");
43 
44  // Min/Max acceptable error to continue aligning with wall
45  nh.param<double>("min_angle", min_angle_, -0.5);
46  nh.param<double>("max_angle", max_angle_, 0.5);
47 
48  // How fast to accelerate
49  nh.param<double>("accel_limit", accel_limit_, 2.0);
50  // Maximum velocity to command base during alignment
51  nh.param<double>("align_velocity", align_velocity_, 0.2);
52  // Gain to turn alignment error into velocity
53  nh.param<double>("align_gain", align_gain_, 2.0);
54  // Tolerance when aligning the base
55  nh.param<double>("align_tolerance", align_tolerance_, 0.2);
56  // Tolerance for r2
57  nh.param<double>("r2_tolerance", r2_tolerance_, 0.1);
58 
59  // Command publisher
60  cmd_pub_ = n.advertise<geometry_msgs::Twist>("cmd_vel", 10);
61 
62  // Subscribe
65  scan_subscriber_ = n.subscribe("base_scan", 1, &BaseCalibration::laserCallback, this);
66 
67  resetInternal();
68 }
69 
71 {
72  scan_.clear();
73  odom_.clear();
74  imu_.clear();
75 }
76 
78 {
79  std::stringstream ss;
80  ss << scan_r2_ << " " << imu_angle_ << " " << odom_angle_ << " " << scan_angle_;
81  return ss.str();
82 }
83 
85 {
86  double odom, imu;
87  ros::NodeHandle nh;
88  nh.param<double>("base_controller/track_width", odom, 0.37476);
89  nh.param<double>("imu/gyro/scale", imu, 0.001221729);
90 
91  // Scaling to be computed
92  double odom_scale = 0.0;
93  double imu_scale = 0.0;
94 
95  // Get sum
96  for (size_t i = 0; i < scan_.size(); ++i)
97  {
98  odom_scale += (scan_[i] - odom_[i]) / odom_[i];
99  imu_scale += (scan_[i] - imu_[i]) / imu_[i];
100  }
101  // Divide sum by size
102  odom_scale /= scan_.size();
103  imu_scale /= scan_.size();
104  // Output odom/imu values
105  std::stringstream ss;
106  ss << "odom: " << odom * (1.0 + odom_scale) << std::endl;
107  ss << "imu: " << imu * (1.0 + imu_scale) << std::endl;
108  return ss.str();
109 }
110 
111 bool BaseCalibration::align(double angle, bool verbose)
112 {
113  while (!ready_)
114  {
115  ROS_WARN("Not ready!");
116  ros::Duration(0.1).sleep();
117  ros::spinOnce();
118  }
119 
120  std::cout << "aligning..." << std::endl;
121 
122  double error = scan_angle_ - angle;
123  while (fabs(error) > align_tolerance_ || (scan_r2_ < r2_tolerance_))
124  {
125  if (verbose)
126  {
127  std::cout << scan_r2_ << " " << scan_angle_ << std::endl;
128  }
129 
130  // Send command
131  double velocity = std::min(std::max(-error * align_gain_, -align_velocity_), align_velocity_);
132  sendVelocityCommand(velocity);
133 
134  // Sleep a moment
135  ros::Duration(0.02).sleep();
136  ros::spinOnce();
137 
138  // Update error before comparing again
139  error = scan_angle_ - angle;
140 
141  // Exit if shutting down
142  if (!ros::ok())
143  {
144  sendVelocityCommand(0.0);
145  return false;
146  }
147  }
148 
149  // Done - stop the robot
150  sendVelocityCommand(0.0);
151  std::cout << "...done" << std::endl;
152  ros::Duration(0.25).sleep();
153 
154  return true;
155 }
156 
157 bool BaseCalibration::spin(double velocity, int rotations, bool verbose)
158 {
159  double scan_start = scan_angle_;
160 
161  // Align straight at the wall
162  align(0.0, verbose);
163  resetInternal();
164  std::cout << "spin..." << std::endl;
165 
166  // Need to account for de-acceleration time (v^2/2a)
167  double angle = rotations * 2 * PI - (0.5 * velocity * velocity / accel_limit_);
168 
169  while (fabs(odom_angle_) < angle)
170  {
171  if (verbose)
172  {
173  std::cout << scan_angle_ << " " << odom_angle_ << " " << imu_angle_ << std::endl;
174  }
175  sendVelocityCommand(velocity);
176  ros::Duration(0.02).sleep();
177  ros::spinOnce();
178 
179  // Exit if shutting down
180  if (!ros::ok())
181  {
182  sendVelocityCommand(0.0);
183  return false;
184  }
185  }
186 
187  // Stop the robot
188  sendVelocityCommand(0.0);
189  std::cout << "...done" << std::endl;
190 
191  // Wait to stop
192  ros::Duration(0.5 + fabs(velocity) / accel_limit_).sleep();
193 
194  // Save measurements
195  imu_.push_back(imu_angle_);
196  odom_.push_back(odom_angle_);
197  if (velocity > 0)
198  {
199  scan_.push_back(scan_start + 2 * rotations * PI - scan_angle_);
200  }
201  else
202  {
203  scan_.push_back(scan_start - 2 * rotations * PI - scan_angle_);
204  }
205 
206  return true;
207 }
208 
209 void BaseCalibration::odometryCallback(const nav_msgs::Odometry::Ptr& odom)
210 {
211  boost::recursive_mutex::scoped_lock lock(data_mutex_);
212 
213  double dt = (odom->header.stamp - last_odom_stamp_).toSec();
214  odom_angle_ += odom->twist.twist.angular.z * dt;
215 
216  last_odom_stamp_ = odom->header.stamp;
217 }
218 
219 void BaseCalibration::imuCallback(const sensor_msgs::Imu::Ptr& imu)
220 {
221  boost::recursive_mutex::scoped_lock lock(data_mutex_);
222 
223  double dt = (imu->header.stamp - last_imu_stamp_).toSec();
224  imu_angle_ += imu->angular_velocity.z * dt;
225 
226  last_imu_stamp_ = imu->header.stamp;
227 }
228 
229 void BaseCalibration::laserCallback(const sensor_msgs::LaserScan::Ptr& scan)
230 {
231  boost::recursive_mutex::scoped_lock lock(data_mutex_);
232 
233  double angle = scan->angle_min;
234  double mean_x, mean_y, n;
235  mean_x = mean_y = n = 0;
236  int start = -1;
237  for (size_t i = 0; i < scan->ranges.size(); ++i, angle += scan->angle_increment)
238  {
239  if (angle < min_angle_ || angle > max_angle_)
240  {
241  continue;
242  }
243 
244  if (std::isnan(scan->ranges[i]))
245  {
246  continue;
247  }
248 
249  if (start < 0)
250  {
251  start = i;
252  }
253 
254  // Compute point
255  double px = sin(angle) * scan->ranges[i];
256  double py = cos(angle) * scan->ranges[i];
257 
258  mean_x += px;
259  mean_y += py;
260  ++n;
261  }
262 
263  if (n == 0)
264  {
265  return;
266  }
267 
268  mean_x /= n;
269  mean_y /= n;
270 
271  angle = scan->angle_min + start * scan->angle_increment; // reset angle
272  double x, y, xx, xy, yy;
273  x = y = xx = xy = yy = n = 0;
274  for (size_t i = start; i < scan->ranges.size(); ++i, angle += scan->angle_increment)
275  {
276  if (angle > max_angle_)
277  {
278  break;
279  }
280 
281  if (std::isnan(scan->ranges[i]))
282  {
283  continue;
284  }
285 
286  // Compute point
287  double px = sin(angle) * scan->ranges[i] - mean_x;
288  double py = cos(angle) * scan->ranges[i] - mean_y;
289 
290  // Sums for simple linear regression
291  xx += px * px;
292  xy += px * py;
293  x += px;
294  y += py;
295  yy += py * py;
296  ++n;
297  }
298 
299  scan_dist_ = mean_y;
300  scan_angle_ = atan2((n*xy-x*y)/(n*xx-x*x), 1.0);
301  scan_r2_ = fabs(xy)/(xx * yy);
302  last_scan_stamp_ = scan->header.stamp;
303  ready_ = true;
304 }
305 
307 {
308  geometry_msgs::Twist twist;
309  twist.angular.z = vel;
310  cmd_pub_.publish(twist);
311 }
312 
314 {
315  boost::recursive_mutex::scoped_lock lock(data_mutex_);
317 }
318 
319 } // namespace robot_calibration
robot_calibration::BaseCalibration::print
std::string print()
Print out current calibration state.
Definition: base_calibration.cpp:77
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
ros::spinOnce
ROSCPP_DECL void spinOnce()
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::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
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
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
y
double y
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
ROS_WARN
#define ROS_WARN(...)
robot_calibration::BaseCalibration::laserCallback
void laserCallback(const sensor_msgs::LaserScan::Ptr &scan)
Definition: base_calibration.cpp:229
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
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
start
ROSCPP_DECL void start()
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
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
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
robot_calibration::BaseCalibration::last_scan_stamp_
ros::Time last_scan_stamp_
Definition: base_calibration.h:84
base_calibration.h
x
double x
PI
#define PI
Definition: base_calibration.cpp:32
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
ros::Duration::sleep
bool sleep() const
robot_calibration::BaseCalibration::resetInternal
void resetInternal()
Reset the odom/imu counters.
Definition: base_calibration.cpp:313
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()
verbose
bool verbose


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