base_calibration_node.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 int main(int argc, char** argv)
33 {
34  ros::init(argc, argv,"base_calibration_node");
35  ros::NodeHandle nh;
36 
37  // For callbacks
39  spinner.start();
40 
42  b.clearMessages();
43 
44  bool verbose = false;
45  nh.param<bool>("verbose", verbose, verbose);
46 
47  // Rotate at several different speeds
48  b.spin(0.5, 1, verbose);
49  b.spin(1.5, 1, verbose);
50  b.spin(3.0, 2, verbose);
51  b.spin(-0.5, 1, verbose);
52  b.spin(-1.5, 1, verbose);
53  b.spin(-3.0, 2, verbose);
54 
55  // TODO: drive towards wall, to calibrate rollout
56 
57  // Output yaml file
58  {
59  // Generate datecode
60  char datecode[80];
61  {
62  std::time_t t = std::time(NULL);
63  std::strftime(datecode, 80, "%Y_%m_%d_%H_%M_%S", std::localtime(&t));
64  }
65  std::stringstream yaml_name;
66  yaml_name << "/tmp/base_calibration_" << datecode << ".yaml";
67  std::ofstream file;
68  file.open(yaml_name.str().c_str());
69  std::string cal = b.printCalibrationData();
70  file << cal;
71  file.close();
72  std::cout << cal;
73  }
74 
75  spinner.stop();
76  return 0;
77 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
robot_calibration::BaseCalibration::printCalibrationData
std::string printCalibrationData()
Print out the calibration data.
Definition: base_calibration.cpp:84
main
int main(int argc, char **argv)
Definition: base_calibration_node.cpp:32
ros::AsyncSpinner
robot_calibration::BaseCalibration
Class for moving the base around and calibrating imu and odometry.
Definition: base_calibration.h:33
robot_calibration::BaseCalibration::spin
bool spin(double velocity, int rotations, bool verbose=false)
Spin and record imu, odom, scan.
Definition: base_calibration.cpp:157
spinner
void spinner()
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
base_calibration.h
robot_calibration::BaseCalibration::clearMessages
void clearMessages()
Clear any received messages.
Definition: base_calibration.cpp:70
t
geometry_msgs::TransformStamped t
ros::NodeHandle
verbose
bool verbose


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