Skip to content

Commit 674e10f

Browse files
committed
Small update
1 parent 4cce9e2 commit 674e10f

File tree

3 files changed

+6
-7
lines changed

3 files changed

+6
-7
lines changed

moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/res/forward_trajectory_parameters.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -3,4 +3,4 @@ forward_trajectory_parameters:
33
type: bool,
44
description: "If a collision is detected should the robot stop at the current pose or continue executing",
55
default_value: false,
6-
}
6+
}

moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/res/servo_solver_parameters.yaml

+4-4
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ servo_solver_parameters:
22
reference_frame: {
33
type: string,
44
description: "Frame that is tracked by servo",
5-
#validation: {
6-
# not_empty<>: []
7-
#}
8-
}
5+
validation: {
6+
not_empty<>: []
7+
}
8+
}

moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/src/servo_solver.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,6 @@ bool ServoSolver::initialize(const rclcpp::Node::SharedPtr& node,
6464
solver_parameters_ = solver_param_listener->get_params();
6565

6666
// Get Servo Parameters
67-
// Get the servo parameters.
6867
const std::string param_namespace = "moveit_servo";
6968
const std::shared_ptr<const servo::ParamListener> servo_param_listener =
7069
std::make_shared<const servo::ParamListener>(node, param_namespace);
@@ -145,7 +144,7 @@ ServoSolver::solve(const robot_trajectory::RobotTrajectory& local_trajectory,
145144
moveit_servo::KinematicState joint_state = servo_->getNextJointState(current_state, target_twist);
146145
const auto status = servo_->getStatus();
147146
// Servo solver feedback is always the status of the first servo iteration
148-
if (feedback_result.feedback.empty())
147+
if (feedback_result.feedback.empty() && status != moveit_servo::StatusCode::NO_WARNING)
149148
{
150149
feedback_result.feedback = moveit_servo::SERVO_STATUS_CODE_MAP.at(status);
151150
}

0 commit comments

Comments
 (0)