Go to the documentation of this file.
23 #include <std_msgs/String.h>
24 #include <robot_calibration_msgs/CalibrationData.h>
25 #include <robot_calibration_msgs/CaptureConfig.h>
63 int main(
int argc,
char** argv)
65 ros::init(argc, argv,
"robot_calibration");
73 std_msgs::String description_msg;
74 std::vector<robot_calibration_msgs::CalibrationData> data;
77 std::string pose_bag_name(
"calibration_poses.bag");
79 pose_bag_name = argv[1];
81 if (pose_bag_name.compare(
"--from-bag") != 0)
85 capture_manager.
init(nh);
88 description_msg.data = capture_manager.
getUrdf();
91 std::vector<robot_calibration_msgs::CaptureConfig> poses;
92 if (pose_bag_name.compare(
"--manual") != 0)
102 ROS_INFO(
"Using manual calibration mode...");
106 for (
unsigned pose_idx = 0;
107 (pose_idx < poses.size() || poses.empty()) &&
ros::ok();
110 robot_calibration_msgs::CalibrationData msg;
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)
119 if (throwaway.compare(
"exit") == 0)
125 std::vector<std::string> features;
128 ROS_WARN(
"Failed to capture sample %u.", pose_idx);
135 if (!capture_manager.
moveToState(poses[pose_idx].joint_states))
137 ROS_WARN(
"Unable to move to desired state for sample %u.", pose_idx);
147 ROS_WARN(
"Failed to capture sample %u.", pose_idx);
152 ROS_INFO(
"Captured pose %u", pose_idx);
163 std::string data_bag_name(
"/tmp/calibration_data.bag");
165 data_bag_name = argv[2];
181 if (nh.
getParam(
"cal_steps", cal_steps))
186 ROS_FATAL(
"Parameter 'cal_steps' should be a struct.");
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;
197 std::string
name =
static_cast<std::string
>(it->first);
203 std::cout <<
"Parameter Offsets:" << std::endl;
204 std::cout << opt.
getOffsets()->getOffsetYAML() << std::endl;
215 std::cout <<
"Parameter Offsets:" << std::endl;
216 std::cout << opt.
getOffsets()->getOffsetYAML() << std::endl;
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
bool init(ros::NodeHandle &nh)
bool captureFeatures(const std::vector< std::string > &feature_names, robot_calibration_msgs::CalibrationData &msg)
bool getPosesFromBag(const std::string &pose_bag_name, std::vector< robot_calibration_msgs::CaptureConfig > &poses)
Load a vector of calibration poses from a bagfile.
int optimize(OptimizationParams ¶ms, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
Run optimization.
boost::shared_ptr< CalibrationOffsetParser > getOffsets()
Class to do optimization.
bool LoadFromROS(ros::NodeHandle &nh)
#define ROS_INFO_STREAM(args)
ValueStruct::iterator iterator
const Type & getType() const
bool moveToState(const sensor_msgs::JointState &state)
Class to hold parameters for optimization.
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.
T param(const std::string ¶m_name, const T &default_val) const
bool exportResults(Optimizer &optimizer, const std::string &initial_urdf, const std::vector< robot_calibration_msgs::CalibrationData > &data)
Write the outputs of a calibration.
int main(int argc, char **argv)
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01