capture_poses.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 <boost/foreach.hpp>
22 #include <ros/ros.h>
23 #include <rosbag/bag.h>
24 #include <rosbag/view.h>
25 #include <rosbag/query.h>
27 
28 namespace robot_calibration
29 {
30 
31 // Load a set of calibration poses
32 bool getPosesFromBag(const std::string& pose_bag_name,
33  std::vector<robot_calibration_msgs::CaptureConfig>& poses)
34 {
35  poses.clear();
36 
37  ROS_INFO_STREAM("Opening " << pose_bag_name);
38  rosbag::Bag bag;
39  try
40  {
41  bag.open(pose_bag_name, rosbag::bagmode::Read);
42  }
43  catch (rosbag::BagException&)
44  {
45  ROS_FATAL_STREAM("Cannot open " << pose_bag_name);
46  return false;
47  }
48  rosbag::View data_view(bag, rosbag::TopicQuery("calibration_joint_states"));
49 
50  BOOST_FOREACH (rosbag::MessageInstance const m, data_view)
51  {
52  robot_calibration_msgs::CaptureConfig::ConstPtr msg = m.instantiate<robot_calibration_msgs::CaptureConfig>();
53  if (msg == NULL)
54  {
55  // Try to load older style bags
56  sensor_msgs::JointState::ConstPtr js_msg = m.instantiate<sensor_msgs::JointState>();
57  if (js_msg != NULL)
58  {
59  robot_calibration_msgs::CaptureConfig config;
60  config.joint_states = *js_msg;
61  poses.push_back(config);
62  }
63  }
64  else
65  {
66  poses.push_back(*msg);
67  }
68  }
69  return true;
70 }
71 
72 } // namespace robot_calibration
rosbag::Bag
rosbag::MessageInstance
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
ros.h
bag.h
poses.h
rosbag::bagmode::Read
Read
rosbag::BagException
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
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rosbag::TopicQuery
view.h
rosbag::View
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
query.h
rosbag::MessageInstance::instantiate
boost::shared_ptr< T > instantiate() const
rosbag::Bag::open
void open(std::string const &filename, uint32_t mode=bagmode::Read)


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