Skip to content

Commit

Permalink
[rosbag] Catch exceptions by const ref. (#1874)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikepurvis authored Feb 4, 2020
1 parent 01276c8 commit 9f81984
Show file tree
Hide file tree
Showing 5 changed files with 18 additions and 18 deletions.
8 changes: 4 additions & 4 deletions tools/rosbag/src/encrypt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,11 +99,11 @@ EncryptorOptions parseOptions(int argc, char** argv)
{
po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
}
catch (boost::program_options::invalid_command_line_syntax& e)
catch (const boost::program_options::invalid_command_line_syntax& e)
{
throw ros::Exception(e.what());
}
catch (boost::program_options::unknown_option& e)
catch (const boost::program_options::unknown_option& e)
{
throw ros::Exception(e.what());
}
Expand Down Expand Up @@ -183,12 +183,12 @@ int main(int argc, char** argv)
{
opts = parseOptions(argc, argv);
}
catch (ros::Exception const& ex)
catch (const ros::Exception& ex)
{
ROS_ERROR("Error reading options: %s", ex.what());
return 1;
}
catch(boost::regex_error const& ex)
catch (const boost::regex_error& ex)
{
ROS_ERROR("Error reading options: %s\n", ex.what());
return 1;
Expand Down
8 changes: 4 additions & 4 deletions tools/rosbag/src/play.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,10 +75,10 @@ rosbag::PlayerOptions parseOptions(int argc, char** argv) {
try
{
po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
} catch (boost::program_options::invalid_command_line_syntax& e)
} catch (const boost::program_options::invalid_command_line_syntax& e)
{
throw ros::Exception(e.what());
} catch (boost::program_options::unknown_option& e)
} catch (const boost::program_options::unknown_option& e)
{
throw ros::Exception(e.what());
}
Expand Down Expand Up @@ -174,7 +174,7 @@ int main(int argc, char** argv) {
try {
opts = parseOptions(argc, argv);
}
catch (ros::Exception const& ex) {
catch (const ros::Exception& ex) {
ROS_ERROR("Error reading options: %s", ex.what());
return 1;
}
Expand All @@ -184,7 +184,7 @@ int main(int argc, char** argv) {
try {
player.publish();
}
catch (std::runtime_error& e) {
catch (const std::runtime_error& e) {
ROS_FATAL("%s", e.what());
return 1;
}
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag/src/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ void Player::publish() {
bag->open(filename, bagmode::Read);
bags_.push_back(bag);
}
catch (BagUnindexedException ex) {
catch (const BagUnindexedException& ex) {
std::cerr << "Bag file " << filename << " is unindexed. Run rosbag reindex." << std::endl;
return;
}
Expand Down
8 changes: 4 additions & 4 deletions tools/rosbag/src/record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,10 +80,10 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
try
{
po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
} catch (boost::program_options::invalid_command_line_syntax& e)
} catch (const boost::program_options::invalid_command_line_syntax& e)
{
throw ros::Exception(e.what());
} catch (boost::program_options::unknown_option& e)
} catch (const boost::program_options::unknown_option& e)
{
throw ros::Exception(e.what());
}
Expand Down Expand Up @@ -284,11 +284,11 @@ int main(int argc, char** argv) {
try {
opts = parseOptions(argc, argv);
}
catch (ros::Exception const& ex) {
catch (const ros::Exception& ex) {
ROS_ERROR("Error reading options: %s", ex.what());
return 1;
}
catch(boost::regex_error const& ex) {
catch(const boost::regex_error& ex) {
ROS_ERROR("Error reading options: %s\n", ex.what());
return 1;
}
Expand Down
10 changes: 5 additions & 5 deletions tools/rosbag/src/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -386,7 +386,7 @@ void Recorder::startWriting() {
try {
bag_.open(write_filename_, bagmode::Write);
}
catch (rosbag::BagException e) {
catch (const rosbag::BagException& e) {
ROS_ERROR("Error writing: %s", e.what());
exit_code_ = 1;
ros::shutdown();
Expand Down Expand Up @@ -483,7 +483,7 @@ void Recorder::doRecord() {
{
checkDisk();
}
catch (rosbag::BagException &ex)
catch (const rosbag::BagException& ex)
{
ROS_ERROR_STREAM(ex.what());
exit_code_ = 1;
Expand Down Expand Up @@ -541,7 +541,7 @@ void Recorder::doRecord() {
if (scheduledCheckDisk() && checkLogging())
bag_.write(out.topic, out.time, *out.msg, out.connection_header);
}
catch (rosbag::BagException &ex)
catch (const rosbag::BagException& ex)
{
ROS_ERROR_STREAM(ex.what());
exit_code_ = 1;
Expand Down Expand Up @@ -574,7 +574,7 @@ void Recorder::doRecordSnapshotter() {
try {
bag_.open(write_filename, bagmode::Write);
}
catch (rosbag::BagException ex) {
catch (const rosbag::BagException& ex) {
ROS_ERROR("Error writing: %s", ex.what());
return;
}
Expand Down Expand Up @@ -692,7 +692,7 @@ bool Recorder::checkDisk() {
{
info = boost::filesystem::space(p);
}
catch (boost::filesystem::filesystem_error &e)
catch (const boost::filesystem::filesystem_error& e)
{
ROS_WARN("Failed to check filesystem stats [%s].", e.what());
writing_enabled_ = false;
Expand Down

0 comments on commit 9f81984

Please sign in to comment.