Skip to content

Commit

Permalink
Remove spurious uses of the inline keyword (RobotLocomotion#13887)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Aug 17, 2020
1 parent 757b1bf commit 3e2efcc
Show file tree
Hide file tree
Showing 10 changed files with 38 additions and 39 deletions.
2 changes: 1 addition & 1 deletion common/autodiff_overloads.h
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ struct dummy_value<Eigen::AutoDiffScalar<DerType>> {
/// implementation of min/max function for AutoDiffScalar type
/// (https://bitbucket.org/eigen/eigen/src/10a1de58614569c9250df88bdfc6402024687bc6/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h?at=default&fileviewer=file-view-default#AutoDiffScalar.h-546).
template <typename DerType1, typename DerType2>
inline Eigen::AutoDiffScalar<
Eigen::AutoDiffScalar<
typename Eigen::internal::remove_all<DerType1>::type::PlainObject>
if_then_else(bool f_cond, const Eigen::AutoDiffScalar<DerType1>& x,
const Eigen::AutoDiffScalar<DerType2>& y) {
Expand Down
2 changes: 1 addition & 1 deletion common/copyable_unique_ptr.h
Original file line number Diff line number Diff line change
Expand Up @@ -380,7 +380,7 @@ class copyable_unique_ptr : public std::unique_ptr<T> {
in a copyable_unique_ptr object. This is equivalent to `os << p.get();`.
@relates copyable_unique_ptr */
template <class charT, class traits, class T>
inline std::basic_ostream<charT, traits>& operator<<(
std::basic_ostream<charT, traits>& operator<<(
std::basic_ostream<charT, traits>& os,
const copyable_unique_ptr<T>& cu_ptr) {
os << cu_ptr.get();
Expand Down
5 changes: 2 additions & 3 deletions common/identifier.h
Original file line number Diff line number Diff line change
Expand Up @@ -213,16 +213,15 @@ class Identifier {
@relates Identifier
*/
template <typename Tag>
inline std::ostream& operator<<(std::ostream& out,
const Identifier<Tag>& id) {
std::ostream& operator<<(std::ostream& out, const Identifier<Tag>& id) {
out << id.get_value();
return out;
}

/** Enables use of identifiers with to_string. It requires ADL to work. So,
it should be invoked as: `to_string(id);` and should be preceded by
`using std::to_string`.*/
template <typename Tag> inline
template <typename Tag>
std::string to_string(const drake::Identifier<Tag>& id) {
return std::to_string(id.get_value());
}
Expand Down
2 changes: 1 addition & 1 deletion multibody/math/spatial_vector.h
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,7 @@ class SpatialVector {
/// Stream insertion operator to write SpatialVector objects into a
/// `std::ostream`. Especially useful for debugging.
/// @relates SpatialVector.
template <template <typename> class SpatialQuantity, typename T> inline
template <template <typename> class SpatialQuantity, typename T>
std::ostream& operator<<(std::ostream& o,
const SpatialVector<SpatialQuantity, T>& V) {
o << "[" << V[0];
Expand Down
2 changes: 1 addition & 1 deletion multibody/tree/rotational_inertia.h
Original file line number Diff line number Diff line change
Expand Up @@ -1034,7 +1034,7 @@ class RotationalInertia {
/// Insertion operator to write %RotationalInertia's into a `std::ostream`.
/// Especially useful for debugging.
/// @relates RotationalInertia
template <typename T> inline
template <typename T>
std::ostream& operator<<(std::ostream& o,
const RotationalInertia<T>& I) {
int width = 0;
Expand Down
2 changes: 1 addition & 1 deletion multibody/tree/spatial_inertia.h
Original file line number Diff line number Diff line change
Expand Up @@ -514,7 +514,7 @@ class SpatialInertia {
/// Insertion operator to write SpatialInertia objects into a `std::ostream`.
/// Especially useful for debugging.
/// @relates SpatialInertia
template <typename T> inline
template <typename T>
std::ostream& operator<<(std::ostream& o,
const SpatialInertia<T>& M) {
return o << std::endl
Expand Down
4 changes: 2 additions & 2 deletions perception/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,8 @@ class PointCloud final {
/// Represents an invalid or uninitialized value.
static constexpr T kDefaultValue = std::numeric_limits<T>::quiet_NaN();
static constexpr C kDefaultColor{};
static inline bool IsDefaultValue(T value) { return std::isnan(value); }
static inline bool IsInvalidValue(T value) { return !std::isfinite(value); }
static bool IsDefaultValue(T value) { return std::isnan(value); }
static bool IsInvalidValue(T value) { return !std::isfinite(value); }

/// Constructs a point cloud of a given `new_size`, with the prescribed
/// `fields`. If `kDescriptors` is one of the fields, then
Expand Down
8 changes: 4 additions & 4 deletions perception/point_cloud_flags.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,12 @@ class DescriptorType final {
: size_(size),
name_(name) {}

inline int size() const { return size_; }
inline std::string name() const { return name_; }
inline bool operator==(const DescriptorType& other) const {
int size() const { return size_; }
std::string name() const { return name_; }
bool operator==(const DescriptorType& other) const {
return size_ == other.size_ && name() == other.name();
}
inline bool operator!=(const DescriptorType& other) const {
bool operator!=(const DescriptorType& other) const {
return !(*this == other);
}

Expand Down
46 changes: 23 additions & 23 deletions systems/controllers/setpoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,22 +115,22 @@ class CartesianSetpoint {
}

// Getters
inline const math::RigidTransform<Scalar>& desired_pose() const {
const math::RigidTransform<Scalar>& desired_pose() const {
return pose_d_;
}
inline const Vector6<Scalar>& desired_velocity() const { return vel_d_; }
inline const Vector6<Scalar>& desired_acceleration() const { return acc_d_; }
inline const Vector6<Scalar>& Kp() const { return Kp_; }
inline const Vector6<Scalar>& Kd() const { return Kd_; }
const Vector6<Scalar>& desired_velocity() const { return vel_d_; }
const Vector6<Scalar>& desired_acceleration() const { return acc_d_; }
const Vector6<Scalar>& Kp() const { return Kp_; }
const Vector6<Scalar>& Kd() const { return Kd_; }

// Setters
inline math::RigidTransform<Scalar>& mutable_desired_pose() {
math::RigidTransform<Scalar>& mutable_desired_pose() {
return pose_d_;
}
inline Vector6<Scalar>& mutable_desired_velocity() { return vel_d_; }
inline Vector6<Scalar>& mutable_desired_acceleration() { return acc_d_; }
inline Vector6<Scalar>& mutable_Kp() { return Kp_; }
inline Vector6<Scalar>& mutable_Kd() { return Kd_; }
Vector6<Scalar>& mutable_desired_velocity() { return vel_d_; }
Vector6<Scalar>& mutable_desired_acceleration() { return acc_d_; }
Vector6<Scalar>& mutable_Kp() { return Kp_; }
Vector6<Scalar>& mutable_Kd() { return Kd_; }

EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Expand All @@ -149,8 +149,8 @@ class CartesianSetpoint {
};

template <typename Scalar>
inline std::ostream& operator<<(std::ostream& out,
const CartesianSetpoint<Scalar>& setpoint) {
std::ostream& operator<<(std::ostream& out,
const CartesianSetpoint<Scalar>& setpoint) {
const math::RigidTransform<Scalar> X(setpoint.desired_pose());
const math::RollPitchYaw<Scalar> rpy(X.rotation());
out << "pose: (" << X.translation().transpose()
Expand Down Expand Up @@ -249,19 +249,19 @@ class VectorSetpoint {
}

// Getters
inline const VectorX<Scalar>& desired_position() const { return pos_d_; }
inline const VectorX<Scalar>& desired_velocity() const { return vel_d_; }
inline const VectorX<Scalar>& desired_acceleration() const { return acc_d_; }
inline const VectorX<Scalar>& Kp() const { return Kp_; }
inline const VectorX<Scalar>& Kd() const { return Kd_; }
inline int size() const { return pos_d_.size(); }
const VectorX<Scalar>& desired_position() const { return pos_d_; }
const VectorX<Scalar>& desired_velocity() const { return vel_d_; }
const VectorX<Scalar>& desired_acceleration() const { return acc_d_; }
const VectorX<Scalar>& Kp() const { return Kp_; }
const VectorX<Scalar>& Kd() const { return Kd_; }
int size() const { return pos_d_.size(); }

// Setters
inline VectorX<Scalar>& mutable_desired_position() { return pos_d_; }
inline VectorX<Scalar>& mutable_desired_velocity() { return vel_d_; }
inline VectorX<Scalar>& mutable_desired_acceleration() { return acc_d_; }
inline VectorX<Scalar>& mutable_Kp() { return Kp_; }
inline VectorX<Scalar>& mutable_Kd() { return Kd_; }
VectorX<Scalar>& mutable_desired_position() { return pos_d_; }
VectorX<Scalar>& mutable_desired_velocity() { return vel_d_; }
VectorX<Scalar>& mutable_desired_acceleration() { return acc_d_; }
VectorX<Scalar>& mutable_Kp() { return Kp_; }
VectorX<Scalar>& mutable_Kd() { return Kd_; }

private:
// Desired position
Expand Down
4 changes: 2 additions & 2 deletions systems/primitives/symbolic_vector_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ Expression FirstOrderTaylorExpand(const Expression& f, const Substitution& a) {
}

// Checks if @p v is in @p variables.
inline bool Includes(const Ref<const VectorX<Variable>>& variables,
const Variable& v) {
bool Includes(const Ref<const VectorX<Variable>>& variables,
const Variable& v) {
for (int i = 0; i < variables.size(); ++i) {
if (variables[i].equal_to(v)) {
return true;
Expand Down

0 comments on commit 3e2efcc

Please sign in to comment.