Skip to content
Snippets Groups Projects
Commit d4b4a572 authored by Christoph Jähne's avatar Christoph Jähne
Browse files

remove const in header for pass by value params

parent 047e4e05
No related branches found
No related tags found
No related merge requests found
...@@ -144,16 +144,16 @@ class FrankaCombinableHW : public FrankaHW { ...@@ -144,16 +144,16 @@ class FrankaCombinableHW : public FrankaHW {
return current_cmd; return current_cmd;
} }
void publishErrorState(const bool error); void publishErrorState(bool error);
void setupServicesAndActionServers(ros::NodeHandle& node_handle); void setupServicesAndActionServers(ros::NodeHandle& node_handle);
void initRobot() override; void initRobot() override;
bool setRunFunction(const ControlMode& requested_control_mode, bool setRunFunction(const ControlMode& requested_control_mode,
const bool limit_rate, bool limit_rate,
const double cutoff_frequency, double cutoff_frequency,
const franka::ControllerMode internal_controller) override; franka::ControllerMode internal_controller) override;
void controlLoop(); void controlLoop();
......
...@@ -262,7 +262,7 @@ class FrankaHW : public hardware_interface::RobotHW { ...@@ -262,7 +262,7 @@ class FrankaHW : public hardware_interface::RobotHW {
* @return True if the array contains NaN values, false otherwise. * @return True if the array contains NaN values, false otherwise.
*/ */
template <size_t size> 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); }); 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 { ...@@ -365,7 +365,7 @@ class FrankaHW : public hardware_interface::RobotHW {
template <typename T> template <typename T>
void setupJointCommandInterface(std::array<double, 7>& command, void setupJointCommandInterface(std::array<double, 7>& command,
franka::RobotState& state, franka::RobotState& state,
const bool use_q_d, bool use_q_d,
T& interface) { T& interface) {
for (size_t i = 0; i < joint_names_.size(); i++) { for (size_t i = 0; i < joint_names_.size(); i++) {
hardware_interface::JointStateHandle state_handle; hardware_interface::JointStateHandle state_handle;
...@@ -427,9 +427,9 @@ class FrankaHW : public hardware_interface::RobotHW { ...@@ -427,9 +427,9 @@ class FrankaHW : public hardware_interface::RobotHW {
* @return True if successful, false otherwise. * @return True if successful, false otherwise.
*/ */
virtual bool setRunFunction(const ControlMode& requested_control_mode, virtual bool setRunFunction(const ControlMode& requested_control_mode,
const bool limit_rate, bool limit_rate,
const double cutoff_frequency, double cutoff_frequency,
const franka::ControllerMode internal_controller); franka::ControllerMode internal_controller);
/** /**
* Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model. * Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
*/ */
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment