Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Better bridge bagger #708

Merged
merged 4 commits into from
Nov 24, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions subt_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ find_package(catkin REQUIRED COMPONENTS
topic_tools
subt_msgs
subt_communication_broker
rosbag
)

add_message_files(
Expand Down
5 changes: 0 additions & 5 deletions subt_ros/launch/competition_init.launch
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,6 @@
name="set_pose_relay"/>
</group>

<!-- rosbag a /robot_data topic which can be used by a team to record
custom data -->
<node pkg="rosbag" type="record" name="rosbag_robot_data"
args="record --split --size=1000 --max-splits=2 -O $(env HOME)/.ros/robot_data.bag -e '/robot_data(.*)'"/>

<node pkg="tf2_ros" type="static_transform_publisher" name="tf_world_static" args="0 0 0 0 0 0 world $(arg world_name)"/>

</launch>
1 change: 1 addition & 0 deletions subt_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<depend>ignition-math6</depend>
<depend>ignition-msgs4</depend>
<depend>ignition-transport7</depend>
<depend>rosbag</depend>
<depend>theora_image_transport</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
Expand Down
37 changes: 37 additions & 0 deletions subt_ros/src/SubtRosRelay.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include <subt_communication_broker/protobuf/datagram.pb.h>
#include <subt_communication_broker/common_types.h>
#include <subt_ros/CompetitionClock.h>
#include <rosbag/recorder.h>

#include <ignition/transport/Node.hh>

Expand Down Expand Up @@ -166,6 +167,12 @@ class SubtRosRelay

/// \brief Name of the robot this relay is associated with.
public: std::vector<std::string> robotNames;

/// \brief Thread on which the ROS bag recorder runs.
public: std::unique_ptr<std::thread> bagThread = nullptr;

/// \brief Pointer to the ROS bag recorder.
public: std::unique_ptr<rosbag::Recorder> rosRecorder;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -222,6 +229,26 @@ SubtRosRelay::SubtRosRelay()
this->rosnode->advertise<std_msgs::Int32>("score", 1000);
this->rosCompetitionClockPub =
this->rosnode->advertise<subt_ros::CompetitionClock>("run_clock", 1000);

// Setup a ros bag recorder.
rosbag::RecorderOptions recorderOptions;
recorderOptions.append_date=false;
recorderOptions.split=true;
recorderOptions.max_splits=1;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Before it was 2 :)

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, please don't make the logs smaller, thanks.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The previous implementation was incorrect. According to the API, up to 2 GB across 2 log files should be recorded. This equates to 1 split, which allows 2 log files.

This PR will produce up two 2 bag files, each with a maximum of 1GB.


// This equation is sourced from line 133 in
// http://docs.ros.org/en/noetic/api/rosbag/html/c++/record_8cpp_source.html
recorderOptions.max_size=1048576 * 1000;

recorderOptions.prefix="robot_data";
recorderOptions.regex=true;
recorderOptions.topics.push_back("/robot_data(.*)");

// Spawn thread for recording /subt/ data to rosbag.
this->rosRecorder.reset(new rosbag::Recorder(recorderOptions));
this->bagThread.reset(new std::thread([&](){
this->rosRecorder->run();
}));
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -255,6 +282,16 @@ void SubtRosRelay::OnCompetitionClock(const ignition::msgs::Clock &_msg)
clockMsg.data.sec = _msg.sim().sec();
clockMsg.data.nsec = _msg.sim().nsec();
this->rosCompetitionClockPub.publish(clockMsg);

// Shutdown when the phase == finished. This makes sure that the rosbag
// ends cleanly.
if (clockMsg.phase == "finished" &&
this->bagThread && this->bagThread->joinable())
{
// Shutdown ros. this makes the ROS bag recorder stop.
ros::shutdown();
this->bagThread->join();
}
}

/////////////////////////////////////////////////
Expand Down