37 #include <boost/foreach.hpp> 39 #include <xpp_msgs/RobotStateCartesian.h> 48 int main(
int argc,
char *argv[])
51 std::cerr <<
"Error: Please enter path to bag file\n";
55 std::string bag_file = argv[1];
59 std::cout <<
"Reading from bag " + bag_r.
getFileName() << std::endl;
62 std::string topic =
"/xpp/state_des";
64 if (view.
size() == 0) {
65 std::cerr <<
"Error: Topic " << topic <<
" doesn't exist\n";
76 auto state_msg = m.
instantiate<xpp_msgs::RobotStateCartesian>();
77 bag_w.
write(
"base_pose", t, state_msg->base.pose);
78 bag_w.
write(
"base_acc", t, state_msg->base.accel.linear);
80 int n_feet = state_msg->ee_motion.size();
82 for (
int i=0; i<n_feet; ++i) {
83 bag_w.
write(
"foot_pos_"+std::to_string(i), t, state_msg->ee_motion.at(i).pos);
84 bag_w.
write(
"foot_force_"+std::to_string(i), t, state_msg->ee_forces.at(i));
89 std::cout <<
"Successfully created bag " + bag_w.
getFileName() << std::endl;
void open(std::string const &filename, uint32_t mode=bagmode::Read)
std::string getFileName() const
geometry_msgs::TransformStamped t
ros::Time const & getTime() const
boost::shared_ptr< T > instantiate() const
void write(std::string const &topic, ros::MessageEvent< T > const &event)