Skip to content

Commit

Permalink
escape literal single-quotes
Browse files Browse the repository at this point in the history
  • Loading branch information
EzraBrooks committed Jun 28, 2024
1 parent 55fe883 commit 1d85309
Show file tree
Hide file tree
Showing 7 changed files with 12 additions and 12 deletions.
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/joint_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ size_t JointModel::getLocalVariableIndex(const std::string& variable) const
{
VariableIndexMap::const_iterator it = variable_index_map_.find(variable);
if (it == variable_index_map_.end())
throw Exception("Could not find variable '" + variable + "' to get bounds for within joint '" + name_ + ''');
throw Exception("Could not find variable '" + variable + "' to get bounds for within joint '" + name_ + '\'');
return it->second;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKSolver)

if (!solver)
{
throw("No IK solver configured for group '" + planning_group_ + ''');
throw("No IK solver configured for group '" + planning_group_ + '\'');
}
// robot state
moveit::core::RobotState rstate(robot_model_);
Expand Down
8 changes: 4 additions & 4 deletions moveit_ros/moveit_servo/src/servo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
"'hard_stop_singularity_threshold' is: '"
<< servo_params.hard_stop_singularity_threshold
<< "' and the 'lower_singularity_threshold' is: '"
<< servo_params.lower_singularity_threshold << ''' << check_yaml_string);
<< servo_params.lower_singularity_threshold << '\'' << check_yaml_string);
params_valid = false;
}

Expand Down Expand Up @@ -234,7 +234,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
"'self_collision_proximity_threshold' is: '"
<< servo_params.self_collision_proximity_threshold
<< "' and 'scene_collision_proximity_threshold' is: '"
<< servo_params.scene_collision_proximity_threshold << ''' << check_yaml_string);
<< servo_params.scene_collision_proximity_threshold << '\'' << check_yaml_string);
params_valid = false;
}

Expand All @@ -244,7 +244,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
RCLCPP_ERROR_STREAM(logger_, "The parameter 'active_subgroup': '"
<< servo_params.active_subgroup
<< "' does not name a valid subgroup of 'joint group': '"
<< servo_params.move_group_name << ''' << check_yaml_string);
<< servo_params.move_group_name << '\'' << check_yaml_string);
params_valid = false;
}
if (servo_params.joint_limit_margins.size() !=
Expand All @@ -256,7 +256,7 @@ bool Servo::validateParams(const servo::Params& servo_params) const
"move group. The size of 'joint_limit_margins' is '"
<< servo_params.joint_limit_margins.size() << "' but the number of joints of the move group '"
<< servo_params.move_group_name << "' is '"
<< robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveVariableCount() << '''
<< robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveVariableCount() << '\''
<< check_yaml_string);

params_valid = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ void MotionPlanningFrame::removeSceneObject()

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

static QString decideStatusText(const moveit::core::AttachedBody* attached_body)
{
QString status_text = ''' + QString::fromStdString(attached_body->getName()) + "' is attached to '" +
QString status_text = '\'' + QString::fromStdString(attached_body->getName()) + "' is attached to '" +
QString::fromStdString(attached_body->getAttachedLinkName()) + "'.";
if (!attached_body->getSubframes().empty())
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -413,7 +413,7 @@ void ControllersWidget::loadControllerScreen(ControllerInfo* this_controller)
else // load the controller name into the widget
{
current_edit_controller_ = this_controller->name_;
controller_edit_widget_->setTitle(QString("Edit Controller '").append(current_edit_controller_.c_str()).append('''));
controller_edit_widget_->setTitle(QString("Edit Controller '").append(current_edit_controller_.c_str()).append('\''));
controller_edit_widget_->showDelete();
controller_edit_widget_->hideNewButtonsWidget(); // not necessary for existing controllers
controller_edit_widget_->showSave(); // this is only for edit mode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -149,11 +149,11 @@ void expectYamlEquivalence(const YAML::Node& generated, const YAML::Node& refere

for (const std::string& key : missing_keys)
{
ADD_FAILURE() << msg_prefix << "is missing the key '" << key << ''';
ADD_FAILURE() << msg_prefix << "is missing the key '" << key << '\'';
}
for (const std::string& key : extra_keys)
{
ADD_FAILURE() << msg_prefix << "has an extra key '" << key << ''';
ADD_FAILURE() << msg_prefix << "has an extra key '" << key << '\'';
}
for (const std::string& key : common_keys)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -594,7 +594,7 @@ void PlanningGroupsWidget::loadGroupScreen(srdf::Model::Group* this_group)
{
current_edit_group_ = this_group->name_;
group_edit_widget_->title_->setText(
QString("Edit Planning Group '").append(current_edit_group_.c_str()).append('''));
QString("Edit Planning Group '").append(current_edit_group_.c_str()).append('\''));
group_edit_widget_->btn_delete_->show();
group_edit_widget_->new_buttons_widget_->hide(); // not necessary for existing groups
group_edit_widget_->btn_save_->show(); // this is only for edit mode
Expand Down

0 comments on commit 1d85309

Please sign in to comment.