Skip to content

Commit d74d26a

Browse files
committed
clang tidy changes
1 parent 4770421 commit d74d26a

File tree

1 file changed

+11
-11
lines changed

1 file changed

+11
-11
lines changed

core/include/moveit/task_constructor/stages/gpd_generator.h

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -129,12 +129,12 @@ DeepGraspPose<ActionSpec>::DeepGraspPose(const std::string& action_name,
129129
found_candidates_(false){
130130

131131
auto& p = properties();
132-
p.template declare<std::string>("eef", "name of end-effector");
133-
p.template declare<std::string>("object");
134-
p.template declare<double>("angle_delta", 0.1, "angular steps (rad)");
132+
p.declare<std::string>("eef", "name of end-effector");
133+
p.declare<std::string>("object");
134+
p.declare<double>("angle_delta", 0.1, "angular steps (rad)");
135135

136-
p.template declare<boost::any>("pregrasp", "pregrasp posture");
137-
p.template declare<boost::any>("grasp", "grasp posture");
136+
p.declare<boost::any>("pregrasp", "pregrasp posture");
137+
p.declare<boost::any>("grasp", "grasp posture");
138138

139139
ROS_INFO_NAMED(LOGNAME, "Waiting for connection to grasp generation action server...");
140140
ActionBaseT::clientPtr_->waitForServer(ros::Duration(ActionBaseT::server_timeout_));
@@ -236,21 +236,21 @@ void DeepGraspPose<ActionSpec>::init(const core::RobotModelConstPtr& robot_model
236236
const auto& props = properties();
237237

238238
// check angle_delta
239-
if (props.template get<double>("angle_delta") == 0.){
239+
if (props.get<double>("angle_delta") == 0.){
240240
errors.push_back(*this, "angle_delta must be non-zero");
241241
}
242242

243243
// check availability of object
244-
props.template get<std::string>("object");
244+
props.get<std::string>("object");
245245
// check availability of eef
246-
const std::string& eef = props.template get<std::string>("eef");
246+
const std::string& eef = props.get<std::string>("eef");
247247
if (!robot_model->hasEndEffector(eef)){
248248
errors.push_back(*this, "unknown end effector: " + eef);
249249
}
250250
else {
251251
// check availability of eef pose
252252
const moveit::core::JointModelGroup* jmg = robot_model->getEndEffector(eef);
253-
const std::string& name = props.template get<std::string>("pregrasp");
253+
const std::string& name = props.get<std::string>("pregrasp");
254254
std::map<std::string, double> m;
255255
if (!jmg->getVariableDefaultPositions(name, m)){
256256
errors.push_back(*this, "unknown end effector pose: " + name);
@@ -273,11 +273,11 @@ void DeepGraspPose<ActionSpec>::compute(){
273273

274274
// set end effector pose
275275
const auto& props = properties();
276-
const std::string& eef = props.template get<std::string>("eef");
276+
const std::string& eef = props.get<std::string>("eef");
277277
const moveit::core::JointModelGroup* jmg = scene->getRobotModel()->getEndEffector(eef);
278278

279279
robot_state::RobotState& robot_state = scene->getCurrentStateNonConst();
280-
robot_state.setToDefaultValues(jmg, props.template get<std::string>("pregrasp"));
280+
robot_state.setToDefaultValues(jmg, props.get<std::string>("pregrasp"));
281281

282282

283283
// compose/send goal

0 commit comments

Comments
 (0)