Skip to content

Commit 5cde780

Browse files
committed
Implement jerk-limited smoothing for Servo
1 parent c2935dc commit 5cde780

File tree

6 files changed

+111
-25
lines changed

6 files changed

+111
-25
lines changed

moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -82,15 +82,21 @@ class RuckigFilterPlugin : public SmoothingBaseClass
8282
const Eigen::VectorXd& accelerations) override;
8383

8484
private:
85-
rclcpp::Node::SharedPtr node_;
86-
void getDefaultJointVelAccelBounds();
85+
/**
86+
* A utility to print Ruckig's internal state
87+
*/
88+
void printRuckigState();
8789

88-
online_signal_smoothing::Params params_;
90+
/**
91+
* A utility to get velocity/acceleration/jerk bounds from the robot model
92+
*/
93+
void getVelAccelJerkBounds();
8994

95+
rclcpp::Node::SharedPtr node_;
96+
online_signal_smoothing::Params params_;
9097
size_t num_joints_;
9198
moveit::core::RobotModelConstPtr robot_model_;
92-
93-
bool have_initial_ruckig_output_ = false;
99+
bool have_initial_ruckig_output_;
94100
std::optional<ruckig::Ruckig<ruckig::DynamicDOFs>> ruckig_;
95101
std::optional<ruckig::InputParameter<ruckig::DynamicDOFs>> ruckig_input_;
96102
std::optional<ruckig::OutputParameter<ruckig::DynamicDOFs>> ruckig_output_;

moveit_core/online_signal_smoothing/src/ruckig_filter.cpp

Lines changed: 70 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -56,20 +56,21 @@ bool RuckigFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::
5656
node_ = node;
5757
num_joints_ = num_joints;
5858
robot_model_ = robot_model;
59+
have_initial_ruckig_output_ = false;
5960

6061
// get node parameters and store in member variables
6162
auto param_listener = online_signal_smoothing::ParamListener(node_);
6263
params_ = param_listener.get_params();
6364

6465
// Ruckig needs the joint vel/accel/jerk bounds.
65-
getDefaultJointVelAccelBounds();
66+
getVelAccelJerkBounds();
6667
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input(num_joints_);
6768
ruckig_input.max_velocity = joint_velocity_bounds_;
6869
ruckig_input.max_acceleration = joint_acceleration_bounds_;
6970
ruckig_input.max_jerk = joint_jerk_bounds_;
70-
// initialize positions. All other quantities are initialized to zero in the constructor.
71-
// This will be overwritten in the first control loop
7271
ruckig_input.current_position = std::vector<double>(num_joints_, 0.0);
72+
ruckig_input.current_velocity = std::vector<double>(num_joints_, 0.0);
73+
ruckig_input.current_acceleration = std::vector<double>(num_joints_, 0.0);
7374
ruckig_input_ = ruckig_input;
7475

7576
ruckig_output_.emplace(ruckig::OutputParameter<ruckig::DynamicDOFs>(num_joints_));
@@ -82,16 +83,60 @@ bool RuckigFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::
8283
bool RuckigFilterPlugin::doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities,
8384
Eigen::VectorXd& accelerations)
8485
{
86+
if (have_initial_ruckig_output_ && ruckig_input_ && ruckig_output_)
87+
{
88+
ruckig_output_->pass_to_input(*ruckig_input_);
89+
}
90+
91+
// Update Ruckig target state
92+
// This assumes stationary at the target (zero vel, zero accel)
93+
ruckig_input_->target_position = std::vector<double>(positions.data(), positions.data() + positions.size());
94+
95+
// Call the Ruckig algorithm
96+
ruckig::Result ruckig_result = ruckig_->update(*ruckig_input_, *ruckig_output_);
97+
98+
// Finished means the target state can be reached in this timestep.
99+
// Working means the target state can be reached but not in this timestep.
100+
// ErrorSynchronizationCalculation means smoothing was successful but the robot will deviate a bit from the desired
101+
// path.
102+
// See https://github.com/pantor/ruckig/blob/master/include/ruckig/input_parameter.hpp
103+
if (ruckig_result != ruckig::Result::Finished && ruckig_result != ruckig::Result::Working &&
104+
ruckig_result != ruckig::Result::ErrorSynchronizationCalculation)
105+
106+
{
107+
RCLCPP_ERROR_STREAM(getLogger(), "Ruckig jerk-limited smoothing failed with code: " << ruckig_result);
108+
printRuckigState();
109+
// Return without modifying the position/vel/accel
110+
have_initial_ruckig_output_ = false;
111+
return true;
112+
}
113+
114+
// Update the target state with Ruckig output
115+
positions = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(ruckig_output_->new_position.data(),
116+
ruckig_output_->new_position.size());
117+
velocities = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(ruckig_output_->new_velocity.data(),
118+
ruckig_output_->new_velocity.size());
119+
accelerations = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(ruckig_output_->new_acceleration.data(),
120+
ruckig_output_->new_acceleration.size());
121+
have_initial_ruckig_output_ = true;
122+
85123
return true;
86124
}
87125

88126
bool RuckigFilterPlugin::reset(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
89127
const Eigen::VectorXd& accelerations)
90128
{
129+
// Initialize Ruckig
130+
ruckig_input_->current_position = std::vector<double>(positions.data(), positions.data() + positions.size());
131+
ruckig_input_->current_velocity = std::vector<double>(velocities.data(), velocities.data() + velocities.size());
132+
ruckig_input_->current_acceleration =
133+
std::vector<double>(accelerations.data(), accelerations.data() + accelerations.size());
134+
135+
have_initial_ruckig_output_ = false;
91136
return true;
92137
}
93138

94-
void RuckigFilterPlugin::getDefaultJointVelAccelBounds()
139+
void RuckigFilterPlugin::getVelAccelJerkBounds()
95140
{
96141
auto joint_model_group = robot_model_->getJointModelGroup(params_.planning_group_name);
97142
for (const auto& joint : joint_model_group->getActiveJointModels())
@@ -105,7 +150,7 @@ void RuckigFilterPlugin::getDefaultJointVelAccelBounds()
105150
}
106151
else
107152
{
108-
RCLCPP_ERROR(getLogger(), "No joint vel limit defined. Exiting for safety.");
153+
RCLCPP_ERROR(getLogger(), "No joint velocity limit defined. Exiting for safety.");
109154
std::exit(EXIT_FAILURE);
110155
}
111156

@@ -116,17 +161,33 @@ void RuckigFilterPlugin::getDefaultJointVelAccelBounds()
116161
}
117162
else
118163
{
119-
RCLCPP_ERROR(getLogger(), "WARNING: No joint accel limit defined. Very large accelerations will be "
120-
"possible.");
164+
RCLCPP_WARN(getLogger(), "No joint acceleration limit defined. Very large accelerations will be "
165+
"possible.");
121166
joint_acceleration_bounds_.push_back(DBL_MAX);
122167
}
123168

124-
// MoveIt and the URDF don't support jerk limits, so use a safe default always
125-
joint_jerk_bounds_.push_back(DEFAULT_JERK_BOUND);
169+
if (bound.jerk_bounded_)
170+
{
171+
// Assume symmetric limits
172+
joint_jerk_bounds_.push_back(bound.max_jerk_);
173+
}
174+
else
175+
{
176+
RCLCPP_ERROR_STREAM(getLogger(), "WARNING: No joint jerk limit defined. A default jerk limit of "
177+
<< DEFAULT_JERK_BOUND << " rad/s^3 has been applied.");
178+
joint_jerk_bounds_.push_back(DEFAULT_JERK_BOUND);
179+
}
126180
}
127181

128182
assert(joint_jerk_bounds_.size() == num_joints_);
129183
}
184+
185+
void RuckigFilterPlugin::printRuckigState()
186+
{
187+
RCLCPP_INFO_STREAM(getLogger(), ruckig_->delta_time << "\nRuckig input:\n"
188+
<< ruckig_input_->to_string() << "\nRuckig output:\n"
189+
<< ruckig_output_->to_string());
190+
}
130191
} // namespace online_signal_smoothing
131192

132193
#include <pluginlib/class_list_macros.hpp>

moveit_ros/moveit_servo/include/moveit_servo/servo.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -118,6 +118,7 @@ class Servo
118118

119119
/**
120120
* \brief Get the current state of the robot as given by planning scene monitor.
121+
* This may block if a current robot state is not available immediately.
121122
* @return The current state of the robot.
122123
*/
123124
KinematicState getCurrentRobotState() const;

moveit_ros/moveit_servo/src/servo.cpp

Lines changed: 21 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -79,16 +79,6 @@ Servo::Servo(const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::P
7979

8080
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
8181

82-
// Load the smoothing plugin
83-
if (servo_params_.use_smoothing)
84-
{
85-
setSmoothingPlugin();
86-
}
87-
else
88-
{
89-
RCLCPP_WARN(logger_, "No smoothing plugin loaded");
90-
}
91-
9282
// Create the collision checker and start collision checking.
9383
collision_monitor_ =
9484
std::make_unique<CollisionMonitor>(planning_scene_monitor_, servo_params_, std::ref(collision_velocity_scale_));
@@ -125,6 +115,17 @@ Servo::Servo(const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::P
125115
joint_name_to_index_maps_.insert(
126116
std::make_pair<std::string, JointNameToMoveGroupIndexMap>(std::string(sub_group_name), std::move(new_map)));
127117
}
118+
119+
// Load the smoothing plugin
120+
if (servo_params_.use_smoothing)
121+
{
122+
setSmoothingPlugin();
123+
}
124+
else
125+
{
126+
RCLCPP_WARN(logger_, "No smoothing plugin loaded");
127+
}
128+
128129
RCLCPP_INFO_STREAM(logger_, "Servo initialized successfully");
129130
}
130131

@@ -645,6 +646,16 @@ std::optional<PoseCommand> Servo::toPlanningFrame(const PoseCommand& command, co
645646

646647
KinematicState Servo::getCurrentRobotState() const
647648
{
649+
bool have_current_state = false;
650+
while (rclcpp::ok() && !have_current_state)
651+
{
652+
have_current_state =
653+
planning_scene_monitor_->getStateMonitor()->waitForCurrentState(rclcpp::Clock(RCL_ROS_TIME).now(), 1.0 /* s */);
654+
if (!have_current_state)
655+
{
656+
RCLCPP_WARN(logger_, "Waiting for the current state");
657+
}
658+
}
648659
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
649660
return extractRobotState(robot_state, servo_params_.move_group_name);
650661
}

moveit_ros/moveit_servo/src/servo_node.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -383,7 +383,6 @@ void ServoNode::servoLoop()
383383
{
384384
// if no new command was created, use current robot state
385385
updateSlidingWindow(current_state, joint_cmd_rolling_window_, servo_params_.max_expected_latency, cur_time);
386-
servo_->resetSmoothing(current_state);
387386
}
388387

389388
status_msg.code = static_cast<int8_t>(servo_->getStatus());

moveit_ros/moveit_servo/src/utils/common.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -499,7 +499,15 @@ KinematicState extractRobotState(const moveit::core::RobotStatePtr& robot_state,
499499
current_state.joint_names = joint_names;
500500
robot_state->copyJointGroupPositions(joint_model_group, current_state.positions);
501501
robot_state->copyJointGroupVelocities(joint_model_group, current_state.velocities);
502+
502503
robot_state->copyJointGroupAccelerations(joint_model_group, current_state.accelerations);
504+
// If any acceleration is nan, set all accelerations to zero
505+
if (std::any_of(current_state.accelerations.begin(), current_state.accelerations.end(),
506+
[](double v) { return isnan(v); }))
507+
{
508+
robot_state->zeroAccelerations();
509+
robot_state->copyJointGroupAccelerations(joint_model_group, current_state.accelerations);
510+
}
503511

504512
return current_state;
505513
}

0 commit comments

Comments
 (0)