Skip to content

Commit

Permalink
Satisfy clang even more
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 5, 2024
1 parent 627b0fd commit 367ed26
Show file tree
Hide file tree
Showing 11 changed files with 43 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -63,10 +63,11 @@ struct AdmittanceState
mass_inv.setZero();
stiffness.setZero();
selected_axes.setZero();
current_joint_pos = Eigen::VectorXd::Zero(num_joints);
joint_pos = Eigen::VectorXd::Zero(num_joints);
joint_vel = Eigen::VectorXd::Zero(num_joints);
joint_acc = Eigen::VectorXd::Zero(num_joints);
auto idx = static_cast<Eigen::Index>(num_joints);
current_joint_pos = Eigen::VectorXd::Zero(idx);
joint_pos = Eigen::VectorXd::Zero(idx);
joint_vel = Eigen::VectorXd::Zero(idx);
joint_acc = Eigen::VectorXd::Zero(idx);
}

Eigen::VectorXd current_joint_pos;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -136,9 +136,11 @@ void AdmittanceRule::apply_parameters_update()

for (size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
{
admittance_state_.mass_inv[i] = 1.0 / parameters_.admittance.mass[i];
admittance_state_.damping[i] = parameters_.admittance.damping_ratio[i] * 2 *
sqrt(admittance_state_.mass[i] * admittance_state_.stiffness[i]);
auto idx = static_cast<Eigen::Index>(i);
admittance_state_.mass_inv[idx] = 1.0 / parameters_.admittance.mass[i];
admittance_state_.damping[idx] =
parameters_.admittance.damping_ratio[i] * 2 *
sqrt(admittance_state_.mass[idx] * admittance_state_.stiffness[idx]);
}
}

Expand Down Expand Up @@ -216,12 +218,13 @@ controller_interface::return_type AdmittanceRule::update(
// update joint desired joint state
for (size_t i = 0; i < num_joints_; ++i)
{
auto idx = static_cast<Eigen::Index>(i);
desired_joint_state.positions[i] =
reference_joint_state.positions[i] + admittance_state_.joint_pos[i];
reference_joint_state.positions[i] + admittance_state_.joint_pos[idx];
desired_joint_state.velocities[i] =
reference_joint_state.velocities[i] + admittance_state_.joint_vel[i];
reference_joint_state.velocities[i] + admittance_state_.joint_vel[idx];
desired_joint_state.accelerations[i] =
reference_joint_state.accelerations[i] + admittance_state_.joint_acc[i];
reference_joint_state.accelerations[i] + admittance_state_.joint_acc[idx];
}

return controller_interface::return_type::OK;
Expand Down Expand Up @@ -334,7 +337,7 @@ void AdmittanceRule::process_wrench_measurements(
new_wrench_base.block<3, 1>(0, 1) -= (cog_world_rot * cog_pos_).cross(end_effector_weight_);

// apply smoothing filter
for (size_t i = 0; i < 6; ++i)
for (Eigen::Index i = 0; i < 6; ++i)
{
wrench_world_(i) = filters::exponentialSmoothing(
new_wrench_base(i), wrench_world_(i), parameters_.ft_sensor.filter_coefficient);
Expand All @@ -345,18 +348,20 @@ const control_msgs::msg::AdmittanceControllerState & AdmittanceRule::get_control
{
for (size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
{
state_message_.stiffness.data[i] = admittance_state_.stiffness[i];
state_message_.damping.data[i] = admittance_state_.damping[i];
state_message_.selected_axes.data[i] = static_cast<bool>(admittance_state_.selected_axes[i]);
state_message_.mass.data[i] = admittance_state_.mass[i];
auto idx = static_cast<Eigen::Index>(i);
state_message_.stiffness.data[i] = admittance_state_.stiffness[idx];
state_message_.damping.data[i] = admittance_state_.damping[idx];
state_message_.selected_axes.data[i] = static_cast<bool>(admittance_state_.selected_axes[idx]);
state_message_.mass.data[i] = admittance_state_.mass[idx];
}

for (size_t i = 0; i < parameters_.joints.size(); ++i)
{
auto idx = static_cast<Eigen::Index>(i);
state_message_.joint_state.name[i] = parameters_.joints[i];
state_message_.joint_state.position[i] = admittance_state_.joint_pos[i];
state_message_.joint_state.velocity[i] = admittance_state_.joint_vel[i];
state_message_.joint_state.effort[i] = admittance_state_.joint_acc[i];
state_message_.joint_state.position[i] = admittance_state_.joint_pos[idx];
state_message_.joint_state.velocity[i] = admittance_state_.joint_vel[idx];
state_message_.joint_state.effort[i] = admittance_state_.joint_acc[idx];
}

state_message_.wrench_base.wrench.force.x = admittance_state_.wrench_base[0];
Expand Down Expand Up @@ -411,7 +416,7 @@ void AdmittanceRule::vec_to_eigen(const std::vector<T1> & data, T2 & matrix)
{
for (auto row = 0; row < matrix.rows(); row++)
{
matrix(row, col) = data[row + col * matrix.rows()];
matrix(row, col) = data[static_cast<size_t>(row + col * matrix.rows())];
}
}
}
Expand Down
4 changes: 2 additions & 2 deletions admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,7 +304,7 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
{
auto it =
std::find(allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
auto index = std::distance(allowed_interface_types_.begin(), it);
auto index = static_cast<size_t>(std::distance(allowed_interface_types_.begin(), it));
if (!controller_interface::get_ordered_interfaces(
state_interfaces_, admittance_->parameters_.joints, interface,
joint_state_interface_[index]))
Expand All @@ -319,7 +319,7 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
{
auto it =
std::find(allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
auto index = std::distance(allowed_interface_types_.begin(), it);
auto index = static_cast<size_t>(std::distance(allowed_interface_types_.begin(), it));
if (!controller_interface::get_ordered_interfaces(
command_interfaces_, command_joint_names_, interface, joint_command_interface_[index]))
{
Expand Down
4 changes: 2 additions & 2 deletions joint_state_broadcaster/test/test_joint_state_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1091,10 +1091,10 @@ void JointStateBroadcasterTest::test_published_dynamic_joint_state_message(
ASSERT_THAT(
dynamic_joint_state_msg->interface_values[i].interface_names,
ElementsAreArray(INTERFACE_NAMES));
const auto index_in_original_order = std::distance(
const auto index_in_original_order = static_cast<size_t>(std::distance(
joint_names_.cbegin(),
std::find(
joint_names_.cbegin(), joint_names_.cend(), dynamic_joint_state_msg->joint_names[i]));
joint_names_.cbegin(), joint_names_.cend(), dynamic_joint_state_msg->joint_names[i])));
ASSERT_THAT(
dynamic_joint_state_msg->interface_values[i].values,
Each(joint_values_[index_in_original_order]));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ SegmentTolerances get_segment_tolerances(
.c_str());
return default_tolerances;
}
auto i = std::distance(joints.cbegin(), it);
auto i = static_cast<size_t>(std::distance(joints.cbegin(), it));
std::string interface = "";
try
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -206,8 +206,8 @@ inline std::vector<size_t> mapping(const T & t1, const T & t2)
}
else
{
const size_t t1_dist = std::distance(t1.begin(), t1_it);
const size_t t2_dist = std::distance(t2.begin(), t2_it);
const size_t t1_dist = static_cast<size_t>(std::distance(t1.begin(), t1_it));
const size_t t2_dist = static_cast<size_t>(std::distance(t2.begin(), t2_it));
mapping_vector[t1_dist] = t2_dist;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -907,7 +907,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
{
auto it =
std::find(allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
auto index = std::distance(allowed_interface_types_.begin(), it);
auto index = static_cast<size_t>(std::distance(allowed_interface_types_.begin(), it));
if (!controller_interface::get_ordered_interfaces(
command_interfaces_, command_joint_names_, interface, joint_command_interface_[index]))
{
Expand All @@ -921,7 +921,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
{
auto it =
std::find(allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
auto index = std::distance(allowed_interface_types_.begin(), it);
auto index = static_cast<size_t>(std::distance(allowed_interface_types_.begin(), it));
if (!controller_interface::get_ordered_interfaces(
state_interfaces_, params_.joints, interface, joint_state_interface_[index]))
{
Expand Down
4 changes: 2 additions & 2 deletions joint_trajectory_controller/src/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,8 +175,8 @@ bool Trajectory::sample(

interpolate_between_points(t0, point, t1, next_point, sample_time, output_state);
}
start_segment_itr = begin() + i;
end_segment_itr = begin() + (i + 1);
start_segment_itr = begin() + static_cast<std::ptrdiff_t>(i);
end_segment_itr = begin() + static_cast<std::ptrdiff_t>(i + 1);
if (search_monotonically_increasing)
{
last_sample_idx_ = i;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -467,7 +467,8 @@ class TrajectoryControllerTest : public ::testing::Test
if (joint_names.empty())
{
traj_msg.joint_names = {
joint_names_.begin(), joint_names_.begin() + points_positions[0].size()};
joint_names_.begin(),
joint_names_.begin() + static_cast<std::ptrdiff_t>(points_positions[0].size())};
}
else
{
Expand Down
2 changes: 1 addition & 1 deletion pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ void PidController::reference_callback(const std::shared_ptr<ControllerReference
break;
}

auto position = std::distance(ref_msg->dof_names.begin(), found_it);
auto position = static_cast<size_t>(std::distance(ref_msg->dof_names.begin(), found_it));
ref_msg->values[position] = msg->values[i];
ref_msg->values_dot[position] = msg->values_dot[i];
}
Expand Down
5 changes: 4 additions & 1 deletion steering_controllers_library/src/steering_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,10 @@ void SteeringOdometry::set_velocity_rolling_window_size(size_t velocity_rolling_
reset_accumulators();
}

void SteeringOdometry::set_odometry_type(const unsigned int type) { config_type_ = type; }
void SteeringOdometry::set_odometry_type(const unsigned int type)
{
config_type_ = static_cast<int>(type);
}

double SteeringOdometry::convert_twist_to_steering_angle(double v_bx, double omega_bz)
{
Expand Down

0 comments on commit 367ed26

Please sign in to comment.