@@ -59,6 +59,10 @@ bool ServoSolver::initialize(const rclcpp::Node::SharedPtr& node,
59
59
planning_scene_monitor_ = planning_scene_monitor;
60
60
node_ = node;
61
61
62
+ const std::shared_ptr<const servo_solver_parameters::ParamListener> solver_param_listener =
63
+ std::make_shared<const servo_solver_parameters::ParamListener>(node, " " );
64
+ solver_parameters_ = solver_param_listener->get_params ();
65
+
62
66
// Get Servo Parameters
63
67
// Get the servo parameters.
64
68
const std::string param_namespace = " moveit_servo" ;
@@ -109,9 +113,9 @@ ServoSolver::solve(const robot_trajectory::RobotTrajectory& local_trajectory,
109
113
target_state.update ();
110
114
111
115
// TF planning_frame -> current EE
112
- Eigen::Isometry3d current_pose = current_state->getFrameTransform (" tcp_welding_gun_link " );
116
+ Eigen::Isometry3d current_pose = current_state->getFrameTransform (solver_parameters_. reference_frame );
113
117
// TF planning -> target EE
114
- Eigen::Isometry3d target_pose = target_state.getFrameTransform (" tcp_welding_gun_link " );
118
+ Eigen::Isometry3d target_pose = target_state.getFrameTransform (solver_parameters_. reference_frame );
115
119
116
120
// current EE -> planning frame * planning frame -> target EE
117
121
Eigen::Isometry3d diff_pose = current_pose.inverse () * target_pose;
@@ -127,33 +131,27 @@ ServoSolver::solve(const robot_trajectory::RobotTrajectory& local_trajectory,
127
131
// Transform goal pose to command frame
128
132
servo_->setCommandType (moveit_servo::CommandType::TWIST);
129
133
moveit_servo::TwistCommand target_twist{
130
- " tcp_welding_gun_link " ,
134
+ solver_parameters_. reference_frame ,
131
135
{ diff_pose.translation ().x () * trans_gain, diff_pose.translation ().y () * trans_gain,
132
136
diff_pose.translation ().z () * trans_gain, axis_angle.axis ().x () * axis_angle.angle () * rot_gain,
133
137
axis_angle.axis ().y () * axis_angle.angle () * rot_gain, axis_angle.axis ().z () * axis_angle.angle () * rot_gain }
134
138
};
135
139
136
- // Start DEBUG uncomment for debugging
137
- // auto msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
138
- // msg->header.stamp = node_->now();
139
- // msg->twist.linear.x = target_twist.velocities[0];
140
- // msg->twist.linear.y = target_twist.velocities[1];
141
- // msg->twist.linear.z = target_twist.velocities[2];
142
- // msg->twist.angular.x =target_twist.velocities[3];
143
- // msg->twist.angular.y =target_twist.velocities[4];
144
- // msg->twist.angular.z =target_twist.velocities[5];
145
- // twist_cmd_pub_->publish(std::move(msg));
146
- // End Debug
147
-
148
140
std::optional<trajectory_msgs::msg::JointTrajectory> trajectory_msg;
141
+ // Create servo commands until a trajectory message can be generated
149
142
while (!trajectory_msg)
150
143
{
151
144
// Calculate next servo command
152
145
moveit_servo::KinematicState joint_state = servo_->getNextJointState (current_state, target_twist);
153
146
const auto status = servo_->getStatus ();
147
+ // Servo solver feedback is always the status of the first servo iteration
148
+ if (feedback_result.feedback .empty ())
149
+ {
150
+ feedback_result.feedback = moveit_servo::SERVO_STATUS_CODE_MAP.at (status);
151
+ }
152
+ // If servo couldn't compute the next joint state, exit local solver without a solution
154
153
if (status == moveit_servo::StatusCode::INVALID)
155
154
{
156
- feedback_result.feedback = " Servo StatusCode 'INVALID'" ;
157
155
return feedback_result;
158
156
}
159
157
moveit_servo::updateSlidingWindow (joint_state, joint_cmd_rolling_window_, servo_parameters_.max_expected_latency ,
0 commit comments