From e4977369f5d6b10ea6193e697bae4411fb968c6e Mon Sep 17 00:00:00 2001 From: AdamPettinger Date: Sat, 28 Aug 2021 16:02:44 +0000 Subject: [PATCH] Address Jere's feedback --- moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h | 6 +++++- moveit_ros/moveit_servo/src/servo_calcs.cpp | 3 +-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h index 3493c17b8a7..c830dbcc8e9 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h @@ -85,7 +85,11 @@ class ServoCalcs ~ServoCalcs(); - /** \brief Start the timer where we do work and publish outputs */ + /** + * Start the timer where we do work and publish outputs + * + * @exception can throw a std::runtime_error if the setup was not completed + */ void start(); /** diff --git a/moveit_ros/moveit_servo/src/servo_calcs.cpp b/moveit_ros/moveit_servo/src/servo_calcs.cpp index c5b442107b2..bf0220f5d5f 100644 --- a/moveit_ros/moveit_servo/src/servo_calcs.cpp +++ b/moveit_ros/moveit_servo/src/servo_calcs.cpp @@ -251,8 +251,7 @@ void ServoCalcs::start() auto check_link_is_known = [this](const std::string& frame_name) { if (!current_state_->knowsFrameTransform(frame_name)) { - std::string error_string = "Unknown frame: " + frame_name; - throw std::runtime_error(error_string); + throw std::runtime_error{ "Unknown frame: " + frame_name }; } }; check_link_is_known(parameters_->planning_frame);