Skip to content

Commit

Permalink
Ensure no uninitialized variables
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe committed Aug 11, 2024
1 parent e501d07 commit 297e4ce
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 15 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ jobs:
ROS_DISTRO: jazzy
env:
CXXFLAGS: >-
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unknown-warning-option
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls
CLANG_TIDY_ARGS: --fix --fix-errors --format-style=file
DOCKER_IMAGE: moveit/moveit2:${{ matrix.env.IMAGE }}
UPSTREAM_WORKSPACE: >
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,13 +94,11 @@ class RuckigFilterPlugin : public SmoothingBaseClass
bool getVelAccelJerkBounds(std::vector<double>& joint_velocity_bounds, std::vector<double>& joint_acceleration_bounds,
std::vector<double>& joint_jerk_bounds);

rclcpp::Node::SharedPtr node_;
/** \brief Parameters loaded from yaml file at runtime */
online_signal_smoothing::Params params_;
size_t num_joints_;
/** \brief The robot model contains the vel/accel/jerk limits that Ruckig requires */
moveit::core::RobotModelConstPtr robot_model_;
bool have_initial_ruckig_output_;
bool have_initial_ruckig_output_ = false;
std::optional<ruckig::Ruckig<ruckig::DynamicDOFs>> ruckig_;
std::optional<ruckig::InputParameter<ruckig::DynamicDOFs>> ruckig_input_;
std::optional<ruckig::OutputParameter<ruckig::DynamicDOFs>> ruckig_output_;
Expand Down
31 changes: 20 additions & 11 deletions moveit_core/online_signal_smoothing/src/ruckig_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,38 +52,41 @@ rclcpp::Logger getLogger()
bool RuckigFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model,
size_t num_joints)
{
node_ = node;
num_joints_ = num_joints;
robot_model_ = robot_model;
have_initial_ruckig_output_ = false;

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

// Ruckig needs the joint vel/accel bounds
// TODO: Ruckig says the jerk bounds can be optional. We require them, for now.
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input(num_joints_);
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input(num_joints);
if (!getVelAccelJerkBounds(ruckig_input.max_velocity, ruckig_input.max_acceleration, ruckig_input.max_jerk))
{
return false;
}
ruckig_input.current_position = std::vector<double>(num_joints_, 0.0);
ruckig_input.current_velocity = std::vector<double>(num_joints_, 0.0);
ruckig_input.current_acceleration = std::vector<double>(num_joints_, 0.0);
ruckig_input.current_position = std::vector<double>(num_joints, 0.0);
ruckig_input.current_velocity = std::vector<double>(num_joints, 0.0);
ruckig_input.current_acceleration = std::vector<double>(num_joints, 0.0);

ruckig_input_ = ruckig_input;

ruckig_output_.emplace(ruckig::OutputParameter<ruckig::DynamicDOFs>(num_joints_));
ruckig_output_.emplace(ruckig::OutputParameter<ruckig::DynamicDOFs>(num_joints));

ruckig_.emplace(ruckig::Ruckig<ruckig::DynamicDOFs>(num_joints_, params_.update_period));
ruckig_.emplace(ruckig::Ruckig<ruckig::DynamicDOFs>(num_joints, params_.update_period));

return true;
}

bool RuckigFilterPlugin::doSmoothing(Eigen::VectorXd& positions, Eigen::VectorXd& velocities,
Eigen::VectorXd& accelerations)
{
if (!ruckig_input_ || !ruckig_output_ || !ruckig_)
{
RCLCPP_ERROR_STREAM(getLogger(), "The Ruckig smoother was not initialized");
return false;
}

if (have_initial_ruckig_output_)
{
ruckig_output_->pass_to_input(*ruckig_input_);
Expand Down Expand Up @@ -141,6 +144,12 @@ bool RuckigFilterPlugin::getVelAccelJerkBounds(std::vector<double>& joint_veloci
std::vector<double>& joint_acceleration_bounds,
std::vector<double>& joint_jerk_bounds)
{
if (!robot_model_)
{
RCLCPP_ERROR(getLogger(), "The robot model was not initialized.");
return false;
}

joint_velocity_bounds.clear();
joint_acceleration_bounds.clear();
joint_jerk_bounds.clear();
Expand All @@ -158,7 +167,7 @@ bool RuckigFilterPlugin::getVelAccelJerkBounds(std::vector<double>& joint_veloci
else
{
RCLCPP_ERROR(getLogger(), "No joint velocity limit defined. Exiting for safety.");
std::exit(EXIT_FAILURE);
return false;
}

if (bound.acceleration_bounded_)
Expand Down

0 comments on commit 297e4ce

Please sign in to comment.