@@ -56,20 +56,21 @@ bool RuckigFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::
56
56
node_ = node;
57
57
num_joints_ = num_joints;
58
58
robot_model_ = robot_model;
59
+ have_initial_ruckig_output_ = false ;
59
60
60
61
// get node parameters and store in member variables
61
62
auto param_listener = online_signal_smoothing::ParamListener (node_);
62
63
params_ = param_listener.get_params ();
63
64
64
65
// Ruckig needs the joint vel/accel/jerk bounds.
65
- getDefaultJointVelAccelBounds ();
66
+ getVelAccelJerkBounds ();
66
67
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input (num_joints_);
67
68
ruckig_input.max_velocity = joint_velocity_bounds_;
68
69
ruckig_input.max_acceleration = joint_acceleration_bounds_;
69
70
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
72
71
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 );
73
74
ruckig_input_ = ruckig_input;
74
75
75
76
ruckig_output_.emplace (ruckig::OutputParameter<ruckig::DynamicDOFs>(num_joints_));
@@ -82,16 +83,60 @@ bool RuckigFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::
82
83
bool RuckigFilterPlugin::doSmoothing (Eigen::VectorXd& positions, Eigen::VectorXd& velocities,
83
84
Eigen::VectorXd& accelerations)
84
85
{
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
+
85
123
return true ;
86
124
}
87
125
88
126
bool RuckigFilterPlugin::reset (const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
89
127
const Eigen::VectorXd& accelerations)
90
128
{
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 ;
91
136
return true ;
92
137
}
93
138
94
- void RuckigFilterPlugin::getDefaultJointVelAccelBounds ()
139
+ void RuckigFilterPlugin::getVelAccelJerkBounds ()
95
140
{
96
141
auto joint_model_group = robot_model_->getJointModelGroup (params_.planning_group_name );
97
142
for (const auto & joint : joint_model_group->getActiveJointModels ())
@@ -105,7 +150,7 @@ void RuckigFilterPlugin::getDefaultJointVelAccelBounds()
105
150
}
106
151
else
107
152
{
108
- RCLCPP_ERROR (getLogger (), " No joint vel limit defined. Exiting for safety." );
153
+ RCLCPP_ERROR (getLogger (), " No joint velocity limit defined. Exiting for safety." );
109
154
std::exit (EXIT_FAILURE);
110
155
}
111
156
@@ -116,17 +161,33 @@ void RuckigFilterPlugin::getDefaultJointVelAccelBounds()
116
161
}
117
162
else
118
163
{
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." );
121
166
joint_acceleration_bounds_.push_back (DBL_MAX);
122
167
}
123
168
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
+ }
126
180
}
127
181
128
182
assert (joint_jerk_bounds_.size () == num_joints_);
129
183
}
184
+
185
+ void RuckigFilterPlugin::printRuckigState ()
186
+ {
187
+ RCLCPP_INFO_STREAM (getLogger (), ruckig_->delta_time << " \n Ruckig input:\n "
188
+ << ruckig_input_->to_string () << " \n Ruckig output:\n "
189
+ << ruckig_output_->to_string ());
190
+ }
130
191
} // namespace online_signal_smoothing
131
192
132
193
#include < pluginlib/class_list_macros.hpp>
0 commit comments