Skip to content

Commit 2f49b95

Browse files
committed
escape literal single-quotes
1 parent 1687fc1 commit 2f49b95

File tree

7 files changed

+12
-12
lines changed

7 files changed

+12
-12
lines changed

moveit_core/robot_model/src/joint_model.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ size_t JointModel::getLocalVariableIndex(const std::string& variable) const
8686
{
8787
VariableIndexMap::const_iterator it = variable_index_map_.find(variable);
8888
if (it == variable_index_map_.end())
89-
throw Exception("Could not find variable '" + variable + "' to get bounds for within joint '" + name_ + ''');
89+
throw Exception("Could not find variable '" + variable + "' to get bounds for within joint '" + name_ + '\'');
9090
return it->second;
9191
}
9292

moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -223,7 +223,7 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKSolver)
223223

224224
if (!solver)
225225
{
226-
throw("No IK solver configured for group '" + planning_group_ + ''');
226+
throw("No IK solver configured for group '" + planning_group_ + '\'');
227227
}
228228
// robot state
229229
moveit::core::RobotState rstate(robot_model_);

moveit_ros/moveit_servo/src/servo.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -202,7 +202,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
202202
"'hard_stop_singularity_threshold' is: '"
203203
<< servo_params.hard_stop_singularity_threshold
204204
<< "' and the 'lower_singularity_threshold' is: '"
205-
<< servo_params.lower_singularity_threshold << ''' << check_yaml_string);
205+
<< servo_params.lower_singularity_threshold << '\'' << check_yaml_string);
206206
params_valid = false;
207207
}
208208

@@ -234,7 +234,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
234234
"'self_collision_proximity_threshold' is: '"
235235
<< servo_params.self_collision_proximity_threshold
236236
<< "' and 'scene_collision_proximity_threshold' is: '"
237-
<< servo_params.scene_collision_proximity_threshold << ''' << check_yaml_string);
237+
<< servo_params.scene_collision_proximity_threshold << '\'' << check_yaml_string);
238238
params_valid = false;
239239
}
240240

@@ -244,7 +244,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
244244
RCLCPP_ERROR_STREAM(logger_, "The parameter 'active_subgroup': '"
245245
<< servo_params.active_subgroup
246246
<< "' does not name a valid subgroup of 'joint group': '"
247-
<< servo_params.move_group_name << ''' << check_yaml_string);
247+
<< servo_params.move_group_name << '\'' << check_yaml_string);
248248
params_valid = false;
249249
}
250250
if (servo_params.joint_limit_margins.size() !=
@@ -256,7 +256,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
256256
"move group. The size of 'joint_limit_margins' is '"
257257
<< servo_params.joint_limit_margins.size() << "' but the number of joints of the move group '"
258258
<< servo_params.move_group_name << "' is '"
259-
<< robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveVariableCount() << '''
259+
<< robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveVariableCount() << '\''
260260
<< check_yaml_string);
261261

262262
params_valid = false;

moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -241,7 +241,7 @@ void MotionPlanningFrame::removeSceneObject()
241241

242242
static QString decideStatusText(const collision_detection::CollisionEnv::ObjectConstPtr& obj)
243243
{
244-
QString status_text = ''' + QString::fromStdString(obj->id_) + "' is a collision object with ";
244+
QString status_text = '\'' + QString::fromStdString(obj->id_) + "' is a collision object with ";
245245
if (obj->shapes_.empty())
246246
{
247247
status_text += "no geometry";
@@ -272,7 +272,7 @@ static QString decideStatusText(const collision_detection::CollisionEnv::ObjectC
272272

273273
static QString decideStatusText(const moveit::core::AttachedBody* attached_body)
274274
{
275-
QString status_text = ''' + QString::fromStdString(attached_body->getName()) + "' is attached to '" +
275+
QString status_text = '\'' + QString::fromStdString(attached_body->getName()) + "' is attached to '" +
276276
QString::fromStdString(attached_body->getAttachedLinkName()) + "'.";
277277
if (!attached_body->getSubframes().empty())
278278
{

moveit_setup_assistant/moveit_setup_controllers/src/controllers_widget.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -413,7 +413,7 @@ void ControllersWidget::loadControllerScreen(ControllerInfo* this_controller)
413413
else // load the controller name into the widget
414414
{
415415
current_edit_controller_ = this_controller->name_;
416-
controller_edit_widget_->setTitle(QString("Edit Controller '").append(current_edit_controller_.c_str()).append('''));
416+
controller_edit_widget_->setTitle(QString("Edit Controller '").append(current_edit_controller_.c_str()).append('\''));
417417
controller_edit_widget_->showDelete();
418418
controller_edit_widget_->hideNewButtonsWidget(); // not necessary for existing controllers
419419
controller_edit_widget_->showSave(); // this is only for edit mode

moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -149,11 +149,11 @@ void expectYamlEquivalence(const YAML::Node& generated, const YAML::Node& refere
149149

150150
for (const std::string& key : missing_keys)
151151
{
152-
ADD_FAILURE() << msg_prefix << "is missing the key '" << key << ''';
152+
ADD_FAILURE() << msg_prefix << "is missing the key '" << key << '\'';
153153
}
154154
for (const std::string& key : extra_keys)
155155
{
156-
ADD_FAILURE() << msg_prefix << "has an extra key '" << key << ''';
156+
ADD_FAILURE() << msg_prefix << "has an extra key '" << key << '\'';
157157
}
158158
for (const std::string& key : common_keys)
159159
{

moveit_setup_assistant/moveit_setup_srdf_plugins/src/planning_groups_widget.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -594,7 +594,7 @@ void PlanningGroupsWidget::loadGroupScreen(srdf::Model::Group* this_group)
594594
{
595595
current_edit_group_ = this_group->name_;
596596
group_edit_widget_->title_->setText(
597-
QString("Edit Planning Group '").append(current_edit_group_.c_str()).append('''));
597+
QString("Edit Planning Group '").append(current_edit_group_.c_str()).append('\''));
598598
group_edit_widget_->btn_delete_->show();
599599
group_edit_widget_->new_buttons_widget_->hide(); // not necessary for existing groups
600600
group_edit_widget_->btn_save_->show(); // this is only for edit mode

0 commit comments

Comments
 (0)