Skip to content

Commit 4cce9e2

Browse files
committed
Cleanup + add description
1 parent 0b10087 commit 4cce9e2

File tree

8 files changed

+68
-46
lines changed

8 files changed

+68
-46
lines changed

moveit_ros/hybrid_planning/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ set(LIBRARIES
3838
# Parameters
3939
local_planner_parameters
4040
hp_manager_parameters
41+
forward_trajectory_parameters
42+
servo_solver_parameters
4143
)
4244

4345
set(THIS_PACKAGE_INCLUDE_DEPENDS
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,13 @@
11
# Forward Trajectory Solver
2+
generate_parameter_library(forward_trajectory_parameters res/forward_trajectory_parameters.yaml)
23
add_library(forward_trajectory_plugin SHARED src/forward_trajectory.cpp)
34
set_target_properties(forward_trajectory_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
5+
target_link_libraries(forward_trajectory_plugin forward_trajectory_parameters)
46
ament_target_dependencies(forward_trajectory_plugin ${THIS_PACKAGE_INCLUDE_DEPENDS})
57

68
# Servo Local Solver
9+
generate_parameter_library(servo_solver_parameters res/servo_solver_parameters.yaml)
710
add_library(servo_local_solver_plugin SHARED src/servo_solver.cpp)
811
set_target_properties(servo_local_solver_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
12+
target_link_libraries(servo_local_solver_plugin servo_solver_parameters)
913
ament_target_dependencies(servo_local_solver_plugin ${THIS_PACKAGE_INCLUDE_DEPENDS})

moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/servo_solver.hpp

+30-20
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,7 @@
3333
*********************************************************************/
3434

3535
/* Author: Sebastian Jahr
36-
Description: Local solver plugin that uses moveit_servo to execute the local trajectory in combination with
37-
replanning capabilities
36+
Description: Local solver plugin that uses moveit_servo steer the robot towards a Cartesian goal point.
3837
*/
3938

4039
#pragma once
@@ -44,17 +43,45 @@
4443
#include <moveit/local_planner/local_constraint_solver_interface.h>
4544

4645
#include <moveit_servo/servo.hpp>
46+
#include <servo_solver_parameters.hpp>
4747

4848
namespace moveit::hybrid_planning
4949
{
50+
/**
51+
* @brief Local solver plugin that utilizes moveit_servo as a local planner
52+
*
53+
*/
5054
class ServoSolver : public moveit::hybrid_planning::LocalConstraintSolverInterface
5155
{
5256
public:
57+
/**
58+
* @brief Initializes moveit servo
59+
*
60+
* @param node
61+
* @param planning_scene_monitor Planning scene monitor to access the current state of the system
62+
* @param group_name UNUSED
63+
* @return True if initialization was successful
64+
*/
5365
bool initialize(const rclcpp::Node::SharedPtr& node,
5466
const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
5567
const std::string& group_name) override;
68+
/**
69+
* @brief Reset rolling window
70+
*
71+
* @return Always returns true
72+
*/
5673
bool reset() override;
5774

75+
/**
76+
* @brief Solves local planning problem with servo. The first waypoint of the local trajectory is used as goal point
77+
* for servo. After computing FK for that waypoint, the difference between the current and goal reference frame is used
78+
* to calculate a twist command for servo. The status of servo is returned as feedback to the hybrid planning manager.
79+
*
80+
* @param local_trajectory Reference trajectory, only the first waypoint is used
81+
* @param local_goal UNUSED
82+
* @param local_solution Joint trajectory containing a sequence of servo commands
83+
* @return moveit_msgs::action::LocalPlanner::Feedback containing the servo status code
84+
*/
5885
moveit_msgs::action::LocalPlanner::Feedback
5986
solve(const robot_trajectory::RobotTrajectory& local_trajectory,
6087
const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> local_goal,
@@ -63,29 +90,12 @@ class ServoSolver : public moveit::hybrid_planning::LocalConstraintSolverInterfa
6390
private:
6491
rclcpp::Node::SharedPtr node_;
6592
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
66-
93+
servo_solver_parameters::Params solver_parameters_;
6794
servo::Params servo_parameters_;
6895

6996
// Servo cpp interface
7097
std::unique_ptr<moveit_servo::Servo> servo_;
7198

72-
// Uncomment for debugging
73-
// rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_cmd_pub_;
74-
75-
rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr traj_cmd_pub_;
76-
bool publish_ = true;
77-
rclcpp::Subscription<std_msgs::msg::Float64>::SharedPtr collision_velocity_scale_sub_;
78-
79-
// Subscribe to laser corrections
80-
rclcpp::Subscription<control_msgs::msg::JointJog>::SharedPtr laser_corrections_sub_;
81-
double laser_correction_ = 0;
82-
83-
// Flag to indicate if replanning is necessary
84-
bool replan_;
85-
86-
// Flag to indicate that replanning is requested
87-
bool feedback_send_;
88-
8999
// Command queue to build trajectory message and add current robot state
90100
std::deque<moveit_servo::KinematicState> joint_cmd_rolling_window_;
91101
};
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
forward_trajectory_parameters:
2+
stop_before_collision: {
3+
type: bool,
4+
description: "If a collision is detected should the robot stop at the current pose or continue executing",
5+
default_value: false,
6+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
servo_solver_parameters:
2+
reference_frame: {
3+
type: string,
4+
description: "Frame that is tracked by servo",
5+
#validation: {
6+
# not_empty<>: []
7+
#}
8+
}

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

+3-9
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
#include <moveit/local_planner/feedback_types.h>
3737
#include <moveit/planning_scene/planning_scene.h>
3838
#include <moveit/robot_state/conversions.h>
39+
#include <forward_trajectory_parameters.hpp>
3940

4041
namespace
4142
{
@@ -50,15 +51,8 @@ bool ForwardTrajectory::initialize(const rclcpp::Node::SharedPtr& node,
5051
const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
5152
const std::string& /* unused */)
5253
{
53-
// Load parameter & initialize member variables
54-
if (node->has_parameter("stop_before_collision"))
55-
{
56-
node->get_parameter<bool>("stop_before_collision", stop_before_collision_);
57-
}
58-
else
59-
{
60-
stop_before_collision_ = node->declare_parameter<bool>("stop_before_collision", false);
61-
}
54+
auto param_listener = forward_trajectory_parameters::ParamListener(node, "");
55+
stop_before_collision_ = param_listener.get_params().stop_before_collision;
6256
node_ = node;
6357
path_invalidation_event_send_ = false;
6458
num_iterations_stuck_ = 0;

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

+14-16
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,10 @@ bool ServoSolver::initialize(const rclcpp::Node::SharedPtr& node,
5959
planning_scene_monitor_ = planning_scene_monitor;
6060
node_ = node;
6161

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+
6266
// Get Servo Parameters
6367
// Get the servo parameters.
6468
const std::string param_namespace = "moveit_servo";
@@ -109,9 +113,9 @@ ServoSolver::solve(const robot_trajectory::RobotTrajectory& local_trajectory,
109113
target_state.update();
110114

111115
// 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);
113117
// 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);
115119

116120
// current EE -> planning frame * planning frame -> target EE
117121
Eigen::Isometry3d diff_pose = current_pose.inverse() * target_pose;
@@ -127,33 +131,27 @@ ServoSolver::solve(const robot_trajectory::RobotTrajectory& local_trajectory,
127131
// Transform goal pose to command frame
128132
servo_->setCommandType(moveit_servo::CommandType::TWIST);
129133
moveit_servo::TwistCommand target_twist{
130-
"tcp_welding_gun_link",
134+
solver_parameters_.reference_frame,
131135
{ diff_pose.translation().x() * trans_gain, diff_pose.translation().y() * trans_gain,
132136
diff_pose.translation().z() * trans_gain, axis_angle.axis().x() * axis_angle.angle() * rot_gain,
133137
axis_angle.axis().y() * axis_angle.angle() * rot_gain, axis_angle.axis().z() * axis_angle.angle() * rot_gain }
134138
};
135139

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-
148140
std::optional<trajectory_msgs::msg::JointTrajectory> trajectory_msg;
141+
// Create servo commands until a trajectory message can be generated
149142
while (!trajectory_msg)
150143
{
151144
// Calculate next servo command
152145
moveit_servo::KinematicState joint_state = servo_->getNextJointState(current_state, target_twist);
153146
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
154153
if (status == moveit_servo::StatusCode::INVALID)
155154
{
156-
feedback_result.feedback = "Servo StatusCode 'INVALID'";
157155
return feedback_result;
158156
}
159157
moveit_servo::updateSlidingWindow(joint_state, joint_cmd_rolling_window_, servo_parameters_.max_expected_latency,

moveit_ros/hybrid_planning/plugins.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,4 +43,4 @@
4343
<description>Uses Servo as a local solver.</description>
4444
</class>
4545
</library>
46-
</class_libraries>
46+
</class_libraries>

0 commit comments

Comments
 (0)