calibrate.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015 Fetch Robotics Inc.
4  * Copyright (C) 2013-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 <ctime>
22 #include <ros/ros.h>
23 #include <std_msgs/String.h>
24 #include <robot_calibration_msgs/CalibrationData.h>
25 #include <robot_calibration_msgs/CaptureConfig.h>
26 
32 
57 /*
58  * usage:
59  * calibrate --manual
60  * calibrate calibration_poses.bag
61  * calibrate --from-bag calibration_data.bag
62  */
63 int main(int argc, char** argv)
64 {
65  ros::init(argc, argv,"robot_calibration");
66  ros::NodeHandle nh("~");
67 
68  // Should we be stupidly verbose?
69  bool verbose;
70  nh.param<bool>("verbose", verbose, false);
71 
72  // The calibration data
73  std_msgs::String description_msg;
74  std::vector<robot_calibration_msgs::CalibrationData> data;
75 
76  // What bag to use to load calibration poses out of (for capture)
77  std::string pose_bag_name("calibration_poses.bag");
78  if (argc > 1)
79  pose_bag_name = argv[1];
80 
81  if (pose_bag_name.compare("--from-bag") != 0)
82  {
83  // No name provided for a calibration bag file, must do capture
84  robot_calibration::CaptureManager capture_manager;
85  capture_manager.init(nh);
86 
87  // Save URDF for calibration/export step
88  description_msg.data = capture_manager.getUrdf();
89 
90  // Load a set of calibration poses
91  std::vector<robot_calibration_msgs::CaptureConfig> poses;
92  if (pose_bag_name.compare("--manual") != 0)
93  {
94  if (!robot_calibration::getPosesFromBag(pose_bag_name, poses))
95  {
96  // Error will be printed in function
97  return -1;
98  }
99  }
100  else
101  {
102  ROS_INFO("Using manual calibration mode...");
103  }
104 
105  // For each pose in the capture sequence.
106  for (unsigned pose_idx = 0;
107  (pose_idx < poses.size() || poses.empty()) && ros::ok();
108  ++pose_idx)
109  {
110  robot_calibration_msgs::CalibrationData msg;
111  if (poses.empty())
112  {
113  // Manual calibration, wait for keypress
114  ROS_INFO("Press [Enter] to capture a sample... (or type 'done' and [Enter] to finish capture)");
115  std::string throwaway;
116  std::getline(std::cin, throwaway);
117  if (throwaway.compare("done") == 0)
118  break;
119  if (throwaway.compare("exit") == 0)
120  return 0;
121  if (!ros::ok())
122  break;
123 
124  // Empty vector causes us to capture all features
125  std::vector<std::string> features;
126  if (!capture_manager.captureFeatures(features, msg))
127  {
128  ROS_WARN("Failed to capture sample %u.", pose_idx);
129  continue;
130  }
131  }
132  else
133  {
134  // Move head/arm to pose
135  if (!capture_manager.moveToState(poses[pose_idx].joint_states))
136  {
137  ROS_WARN("Unable to move to desired state for sample %u.", pose_idx);
138  continue;
139  }
140 
141  // Make sure sensor data is up to date after settling
142  ros::Duration(0.1).sleep();
143 
144  // Get pose of the features
145  if (!capture_manager.captureFeatures(poses[pose_idx].features, msg))
146  {
147  ROS_WARN("Failed to capture sample %u.", pose_idx);
148  continue;
149  }
150  }
151 
152  ROS_INFO("Captured pose %u", pose_idx);
153 
154  // Add to samples
155  data.push_back(msg);
156  }
157 
158  ROS_INFO("Done capturing samples");
159  }
160  else
161  {
162  // Load calibration data from bagfile
163  std::string data_bag_name("/tmp/calibration_data.bag");
164  if (argc > 2)
165  data_bag_name = argv[2];
166  ROS_INFO_STREAM("Loading calibration data from " << data_bag_name);
167 
168  if (!robot_calibration::load_bag(data_bag_name, description_msg, data))
169  {
170  // Error will have been printed in function
171  return -1;
172  }
173  }
174 
175  // Create instance of optimizer
177  robot_calibration::Optimizer opt(description_msg.data);
178 
179  // Load calibration steps (if any)
180  XmlRpc::XmlRpcValue cal_steps;
181  if (nh.getParam("cal_steps", cal_steps))
182  {
183  // Should be a struct (mapping name -> config)
184  if (cal_steps.getType() != XmlRpc::XmlRpcValue::TypeStruct)
185  {
186  ROS_FATAL("Parameter 'cal_steps' should be a struct.");
187  return false;
188  }
189 
191  size_t step;
192  size_t max_step = (cal_steps.size()>0)?cal_steps.size():1;
193  std::vector<std::string> prev_frame_names;
194  std::string prev_params_yaml;
195  for (step = 0, it = cal_steps.begin(); step < max_step; step++, it++)
196  {
197  std::string name = static_cast<std::string>(it->first);
198  ros::NodeHandle cal_steps_handle(nh, "cal_steps/"+name);
199  params.LoadFromROS(cal_steps_handle);
200  opt.optimize(params, data, verbose);
201  if (verbose)
202  {
203  std::cout << "Parameter Offsets:" << std::endl;
204  std::cout << opt.getOffsets()->getOffsetYAML() << std::endl;
205  }
206  }
207  }
208  else
209  {
210  // Single step calibration
211  params.LoadFromROS(nh);
212  opt.optimize(params, data, verbose);
213  if (verbose)
214  {
215  std::cout << "Parameter Offsets:" << std::endl;
216  std::cout << opt.getOffsets()->getOffsetYAML() << std::endl;
217  }
218  }
219 
220  // Write outputs
221  robot_calibration::exportResults(opt, description_msg.data, data);
222 
223  ROS_INFO("Done calibrating");
224 
225  return 0;
226 }
XmlRpc::XmlRpcValue::size
int size() const
robot_calibration::CaptureManager::getUrdf
std::string getUrdf()
Definition: capture_manager.cpp:91
load_bag.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
capture_manager.h
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
robot_calibration::CaptureManager::init
bool init(ros::NodeHandle &nh)
Definition: capture_manager.cpp:32
step
unsigned int step
robot_calibration::CaptureManager::captureFeatures
bool captureFeatures(const std::vector< std::string > &feature_names, robot_calibration_msgs::CalibrationData &msg)
Definition: capture_manager.cpp:70
poses.h
ros::ok
ROSCPP_DECL bool ok()
robot_calibration::CaptureManager
Definition: capture_manager.h:31
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
robot_calibration::getPosesFromBag
bool getPosesFromBag(const std::string &pose_bag_name, std::vector< robot_calibration_msgs::CaptureConfig > &poses)
Load a vector of calibration poses from a bagfile.
Definition: capture_poses.cpp:32
robot_calibration::Optimizer::optimize
int optimize(OptimizationParams &params, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
Run optimization.
Definition: optimizer.cpp:63
name
std::string name
robot_calibration::Optimizer::getOffsets
boost::shared_ptr< CalibrationOffsetParser > getOffsets()
Definition: optimizer.h:68
robot_calibration::Optimizer
Class to do optimization.
Definition: optimizer.h:42
robot_calibration::OptimizationParams::LoadFromROS
bool LoadFromROS(ros::NodeHandle &nh)
Definition: optimization_params.cpp:30
ROS_WARN
#define ROS_WARN(...)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
XmlRpc::XmlRpcValue::iterator
ValueStruct::iterator iterator
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_FATAL
#define ROS_FATAL(...)
robot_calibration::CaptureManager::moveToState
bool moveToState(const sensor_msgs::JointState &state)
Definition: capture_manager.cpp:58
robot_calibration::OptimizationParams
Class to hold parameters for optimization.
Definition: optimization_params.h:29
robot_calibration::load_bag
bool load_bag(const std::string &file_name, std_msgs::String &description_msg, std::vector< robot_calibration_msgs::CalibrationData > &data)
Load a bagfile of calibration data.
Definition: load_bag.h:42
optimizer.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Duration::sleep
bool sleep() const
XmlRpc::XmlRpcValue::begin
iterator begin()
ROS_INFO
#define ROS_INFO(...)
robot_calibration::exportResults
bool exportResults(Optimizer &optimizer, const std::string &initial_urdf, const std::vector< robot_calibration_msgs::CalibrationData > &data)
Write the outputs of a calibration.
Definition: calibration_export.cpp:28
ros::Duration
main
int main(int argc, char **argv)
Definition: calibrate.cpp:63
XmlRpc::XmlRpcValue
ros::NodeHandle
verbose
bool verbose
export.h


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