From c6a7a4d474ade0ffe4e51f4e9fb180406ef34947 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20J=C3=A4hne?= <christoph.jaehne@franka.de> Date: Tue, 6 Aug 2019 10:32:41 +0200 Subject: [PATCH] use rt config in robot creation --- franka_hw/src/franka_hw.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/franka_hw/src/franka_hw.cpp b/franka_hw/src/franka_hw.cpp index 40d9ac6..ddcc1ca 100644 --- a/franka_hw/src/franka_hw.cpp +++ b/franka_hw/src/franka_hw.cpp @@ -509,7 +509,7 @@ void FrankaHW::initROSInterfaces(ros::NodeHandle& /*robot_hw_nh*/) { } void FrankaHW::initRobot() { - robot_ = std::make_unique<franka::Robot>(robot_ip_); + robot_ = std::make_unique<franka::Robot>(robot_ip_, realtime_config_); model_ = std::make_unique<franka::Model>(robot_->loadModel()); robot_->setCollisionBehavior(collision_config_.lower_torque_thresholds_acceleration, collision_config_.upper_torque_thresholds_acceleration, -- GitLab