21 #ifndef ROBOT_CALIBRATION_LOAD_BAG_H 22 #define ROBOT_CALIBRATION_LOAD_BAG_H 28 #include <boost/foreach.hpp> 30 #include <std_msgs/String.h> 31 #include <robot_calibration_msgs/CalibrationData.h> 43 std_msgs::String& description_msg,
44 std::vector<robot_calibration_msgs::CalibrationData>& data)
60 if (model_view_.
size() < 1)
65 std_msgs::String::ConstPtr description_ = model_view_.
begin()->instantiate<std_msgs::String>();
66 description_msg = *description_;
72 robot_calibration_msgs::CalibrationData::ConstPtr msg = m.
instantiate<robot_calibration_msgs::CalibrationData>();
81 #endif // ROBOT_CALIBRATION_LOAD_BAG_H
void open(std::string const &filename, uint32_t mode=bagmode::Read)
#define ROS_FATAL_STREAM(args)
boost::shared_ptr< T > instantiate() const
Calibration code lives under this namespace.
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.