diff --git a/franka_hw/include/franka_hw/franka_combinable_hw.h b/franka_hw/include/franka_hw/franka_combinable_hw.h
index 214473f7b1f6bf369414a892b60211988ad76d75..bc2dffd8da5f550d041bf5204b9d318fe3f20f3b 100644
--- a/franka_hw/include/franka_hw/franka_combinable_hw.h
+++ b/franka_hw/include/franka_hw/franka_combinable_hw.h
@@ -144,16 +144,16 @@ class FrankaCombinableHW : public FrankaHW {
     return current_cmd;
   }
 
-  void publishErrorState(const bool error);
+  void publishErrorState(bool error);
 
   void setupServicesAndActionServers(ros::NodeHandle& node_handle);
 
   void initRobot() override;
 
   bool setRunFunction(const ControlMode& requested_control_mode,
-                      const bool limit_rate,
-                      const double cutoff_frequency,
-                      const franka::ControllerMode internal_controller) override;
+                      bool limit_rate,
+                      double cutoff_frequency,
+                      franka::ControllerMode internal_controller) override;
 
   void controlLoop();
 
diff --git a/franka_hw/include/franka_hw/franka_hw.h b/franka_hw/include/franka_hw/franka_hw.h
index e17a9b992c30a19894a8b1367d3ead6c3715b88c..2b6ee5eb2b17be4d2dd44bf9493e29647c00daf0 100644
--- a/franka_hw/include/franka_hw/franka_hw.h
+++ b/franka_hw/include/franka_hw/franka_hw.h
@@ -262,7 +262,7 @@ class FrankaHW : public hardware_interface::RobotHW {
    * @return True if the array contains NaN values, false otherwise.
    */
   template <size_t size>
-  static bool arrayHasNaN(const std::array<double, size> array) {
+  static bool arrayHasNaN(const std::array<double, size>& array) {
     return std::any_of(array.begin(), array.end(), [](const double& e) { return std::isnan(e); });
   }
 
@@ -365,7 +365,7 @@ class FrankaHW : public hardware_interface::RobotHW {
   template <typename T>
   void setupJointCommandInterface(std::array<double, 7>& command,
                                   franka::RobotState& state,
-                                  const bool use_q_d,
+                                  bool use_q_d,
                                   T& interface) {
     for (size_t i = 0; i < joint_names_.size(); i++) {
       hardware_interface::JointStateHandle state_handle;
@@ -427,9 +427,9 @@ class FrankaHW : public hardware_interface::RobotHW {
    * @return True if successful, false otherwise.
    */
   virtual bool setRunFunction(const ControlMode& requested_control_mode,
-                              const bool limit_rate,
-                              const double cutoff_frequency,
-                              const franka::ControllerMode internal_controller);
+                              bool limit_rate,
+                              double cutoff_frequency,
+                              franka::ControllerMode internal_controller);
   /**
    * Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
    */