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

getCollisionThresholds -> static, linter fix for string concatenation

parent 3ac977cf
No related branches found
No related tags found
No related merge requests found
......@@ -445,9 +445,9 @@ class FrankaHW : public hardware_interface::RobotHW {
* to be valid.
* @return A set parsed parameters if valid parameters where found, the default values otherwise.
*/
virtual std::vector<double> getCollisionThresholds(const std::string& name,
static std::vector<double> getCollisionThresholds(const std::string& name,
ros::NodeHandle& robot_hw_nh,
const std::vector<double>& defaults) const;
const std::vector<double>& defaults);
struct CollisionConfig {
std::array<double, 7> lower_torque_thresholds_acceleration;
......
......@@ -562,13 +562,14 @@ bool FrankaHW::commandHasNaN(const franka::CartesianVelocities& command) {
std::vector<double> FrankaHW::getCollisionThresholds(const std::string& name,
ros::NodeHandle& robot_hw_nh,
const std::vector<double>& defaults) const {
const std::vector<double>& defaults) {
std::vector<double> thresholds;
if (!robot_hw_nh.getParam("collision_config/" + name, thresholds) ||
thresholds.size() != defaults.size()) {
std::string message;
for (const double& threshold : defaults) {
message = message + std::to_string(threshold) + " ";
message += std::to_string(threshold);
message += " ";
}
ROS_INFO("No parameter %s found, using default values: %s", name.c_str(), message.c_str());
return defaults;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment