franka_combinable_hw.cpp
Go to the documentation of this file.
1 // Copyright (c) 2019 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
4 
5 #include <chrono>
6 #include <thread>
7 
11 #include <std_msgs/Bool.h>
12 
13 #include <franka_hw/services.h>
14 
15 using namespace std::chrono_literals;
16 
17 namespace franka_hw {
18 
19 FrankaCombinableHW::FrankaCombinableHW() : has_error_(false), error_recovered_(false) {}
20 
22  robot_hw_nh_ = robot_hw_nh;
23  return FrankaHW::init(root_nh, robot_hw_nh);
24 }
25 
30  setupLimitInterface<joint_limits_interface::EffortJointSoftLimitsHandle>(
34 
35  has_error_pub_ = robot_hw_nh.advertise<std_msgs::Bool>("has_error", 1, true);
37 
38  setupServicesAndActionServers(robot_hw_nh);
39 }
40 
43  control_loop_thread_ = std::make_unique<std::thread>(&FrankaCombinableHW::controlLoop, this);
44 }
45 
46 void FrankaCombinableHW::publishErrorState(const bool error) {
47  std_msgs::Bool msg;
48  msg.data = static_cast<int>(error);
50 }
51 
53  while (ros::ok()) {
54  ros::Time last_time = ros::Time::now();
55 
56  // Wait until controller has been activated or error has been recovered
57  while (!controllerActive() || has_error_) {
58  if (!controllerActive()) {
59  ROS_DEBUG_THROTTLE(1, "FrankaCombinableHW::%s::control_loop(): controller is not active.",
60  arm_id_.c_str());
61  }
62  if (has_error_) {
63  ROS_DEBUG_THROTTLE(1, "FrankaCombinableHW::%s::control_loop(): an error has occured.",
64  arm_id_.c_str());
65  }
66 
67  if (initialized_) {
69  }
70  {
71  std::lock_guard<std::mutex> robot_lock(robot_mutex_);
72  if (connected()) {
73  std::lock_guard<std::mutex> ros_state_lock(ros_state_mutex_);
74  std::lock_guard<std::mutex> libfranka_state_lock(libfranka_state_mutex_);
75  robot_state_libfranka_ = robot_->readOnce();
76  robot_state_ros_ = robot_->readOnce();
77  }
78  }
79 
80  if (!ros::ok()) {
81  return;
82  }
83  std::this_thread::sleep_for(1ms);
84  }
85  ROS_INFO("FrankaCombinableHW::%s::control_loop(): controller is active.", arm_id_.c_str());
86 
87  // Reset commands
88  {
89  std::lock_guard<std::mutex> libfranka_command_lock(libfranka_cmd_mutex_);
90  std::lock_guard<std::mutex> ros_command_lock(ros_cmd_mutex_);
91  effort_joint_command_libfranka_ = franka::Torques({0., 0., 0., 0., 0., 0., 0.});
92  effort_joint_command_ros_ = franka::Torques({0., 0., 0., 0., 0., 0., 0.});
93  }
94 
95  try {
96  if (connected()) {
97  control();
98  }
99  } catch (const franka::ControlException& e) {
100  // Reflex could be caught and it needs to wait for automatic error recovery
101  ROS_ERROR("%s: %s", arm_id_.c_str(), e.what());
102  has_error_ = true;
104  }
105  }
106 }
107 
109  if (!connected()) {
110  ROS_ERROR(
111  "FrankaCombinableHW::setupServicesAndActionServers: Cannot create services without "
112  "connected robot.");
113  return;
114  }
115 
116  services_ = std::make_unique<ServiceContainer>();
117  setupServices(*robot_, robot_mutex_, node_handle, *services_);
118 
121  std::make_unique<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>(
122  node_handle, "error_recovery",
123  [&](const franka_msgs::ErrorRecoveryGoalConstPtr&) {
124  if (connected()) {
125  try {
126  std::lock_guard<std::mutex> lock(robot_mutex_);
127  robot_->automaticErrorRecovery();
128  // error recovered => reset controller
129  if (has_error_) {
130  error_recovered_ = true;
131  }
132  has_error_ = false;
134  recovery_action_server_->setSucceeded();
135  } catch (const franka::Exception& ex) {
136  recovery_action_server_->setAborted(franka_msgs::ErrorRecoveryResult(),
137  ex.what());
138  }
139  } else {
140  recovery_action_server_->setAborted(franka_msgs::ErrorRecoveryResult(),
141  "Cannot recovery robot while disconnected.");
142  }
143  },
144  false);
145  recovery_action_server_->start();
146  }
147 }
148 
152 }
153 
155  if (controllerActive()) {
156  ROS_ERROR("FrankaHW: Rejected attempt to disconnect while controller is still running!");
157  return false;
158  }
159  recovery_action_server_.reset();
160  services_.reset();
161  return FrankaHW::disconnect();
162 }
163 
164 void FrankaCombinableHW::control( // NOLINT (google-default-arguments)
165  const std::function<bool(const ros::Time&, const ros::Duration&)>& /*ros_callback*/) {
166  if (!controller_active_) {
167  return;
168  }
169  auto empty_method = [](const franka::RobotState&, franka::Duration) { return true; };
170  run_function_(*robot_, empty_method);
171 }
172 
174  const std::list<hardware_interface::ControllerInfo>& info) const {
175  ResourceWithClaimsMap resource_map = getResourceMap(info);
176 
177  if (hasConflictingMultiClaim(resource_map)) {
178  return true;
179  }
180 
181  ArmClaimedMap arm_claim_map;
182  if (!getArmClaimedMap(resource_map, arm_claim_map)) {
183  ROS_ERROR("FrankaCombinableHW: Unknown interface claimed. Conflict!");
184  return true;
185  }
186 
187  // check for any claim to trajectory interfaces (non-torque) which are not supported.
188  if (hasTrajectoryClaim(arm_claim_map, arm_id_)) {
189  ROS_ERROR_STREAM("FrankaCombinableHW: Invalid claim joint position or velocity interface."
190  << "Note: joint position and joint velocity interfaces are not supported"
191  << " in FrankaCombinableHW. Arm:" << arm_id_ << ". Conflict!");
192  return true;
193  }
194 
195  return partiallyClaimsArmJoints(arm_claim_map, arm_id_);
196 }
197 
198 void FrankaCombinableHW::read(const ros::Time& time, const ros::Duration& period) {
200  FrankaHW::read(time, period);
201 }
202 
203 void FrankaCombinableHW::write(const ros::Time& time, const ros::Duration& period) {
204  // if flag `controller_needs_reset_` was updated, then controller_manager. update(...,
205  // reset_controller) must
206  // have been executed to reset the controller.
208  controller_needs_reset_ = false;
209  error_recovered_ = false;
210  }
211 
212  enforceLimits(period);
213 
214  FrankaHW::write(time, period);
215 }
216 
217 std::string FrankaCombinableHW::getArmID() const noexcept {
218  return arm_id_;
219 }
220 
222  has_error_ = true;
224 }
225 
226 bool FrankaCombinableHW::hasError() const noexcept {
227  return has_error_;
228 }
229 
231  if (connected()) {
232  robot_->automaticErrorRecovery();
233  }
234  // error recovered => reset controller
235  if (has_error_) {
236  error_recovered_ = true;
237  }
238  has_error_ = false;
240 }
241 
244 }
245 
246 bool FrankaCombinableHW::setRunFunction(const ControlMode& requested_control_mode,
247  const bool limit_rate,
248  const double cutoff_frequency,
249  const franka::ControllerMode /*internal_controller*/) {
250  using Callback = std::function<bool(const franka::RobotState&, franka::Duration)>;
251 
252  if (requested_control_mode == ControlMode::None) {
253  return true;
254  }
255  if (requested_control_mode == ControlMode::JointTorque) {
256  run_function_ = [this, limit_rate, cutoff_frequency](franka::Robot& robot,
257  Callback /*callback*/) {
258  std::lock_guard<std::mutex> lock(robot_mutex_);
259  robot.control(std::bind(&FrankaCombinableHW::libfrankaUpdateCallback<franka::Torques>, this,
260  std::cref(effort_joint_command_libfranka_), std::placeholders::_1,
261  std::placeholders::_2),
262  limit_rate, cutoff_frequency);
263  };
264  return true;
265  }
266 
267  ROS_ERROR("FrankaCombinableHW: No valid control mode selected; cannot set run function.");
268  return false;
269 }
270 
271 } // namespace franka_hw
272 
franka_hw::FrankaCombinableHW::read
void read(const ros::Time &, const ros::Duration &) override
Reads data from the franka robot.
Definition: franka_combinable_hw.cpp:198
franka_hw::FrankaHW::libfranka_state_mutex_
std::mutex libfranka_state_mutex_
Definition: franka_hw.h:504
franka_hw::FrankaCombinableHW::services_
std::unique_ptr< ServiceContainer > services_
Definition: franka_combinable_hw.h:184
franka_hw::ControlMode::None
@ None
franka_hw::FrankaHW::setupJointCommandInterface
void setupJointCommandInterface(std::array< double, 7 > &command, franka::RobotState &state, bool use_q_d, T &interface)
Configures and registers a joint command interface for positions velocities or efforts in ros_control...
Definition: franka_hw.h:408
franka_hw::FrankaCombinableHW::publishErrorState
void publishErrorState(bool error)
Definition: franka_combinable_hw.cpp:46
franka_hw::FrankaCombinableHW::connect
void connect() override
Create a libfranka robot, connecting the hardware class to the master controller.
Definition: franka_combinable_hw.cpp:149
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
franka_hw::getArmClaimedMap
bool getArmClaimedMap(ResourceWithClaimsMap &resource_map, ArmClaimedMap &arm_claim_map)
Definition: resource_helpers.cpp:41
franka_hw::ControlMode
ControlMode
Definition: control_mode.h:10
franka_hw::FrankaCombinableHW::controller_needs_reset_
std::atomic_bool controller_needs_reset_
Definition: franka_combinable_hw.h:190
franka_hw::FrankaCombinableHW::init
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
Definition: franka_combinable_hw.cpp:21
franka_hw::FrankaCombinableHW::getArmID
std::string getArmID() const noexcept
Getter method for the arm_id which is used to distinguish between multiple instances of FrankaCombina...
Definition: franka_combinable_hw.cpp:217
franka_hw::FrankaHW::setupFrankaModelInterface
virtual void setupFrankaModelInterface(franka::RobotState &robot_state)
Configures and registers the model interface offering kinematics and dynamics in ros_control.
Definition: franka_hw.cpp:427
joint_limits_interface.h
franka_hw::FrankaHW::controllerActive
virtual bool controllerActive() const noexcept
Indicates whether there is an active controller.
Definition: franka_hw.cpp:213
franka_hw::FrankaCombinableHW::controllerNeedsReset
bool controllerNeedsReset() const noexcept
Returns whether the controller needs to be reset e.g.
Definition: franka_combinable_hw.cpp:242
franka_hw::FrankaCombinableHW
A hardware class for a Panda robot based on the ros_control framework.
Definition: franka_combinable_hw.h:30
franka_hw::FrankaHW::ros_cmd_mutex_
std::mutex ros_cmd_mutex_
Definition: franka_hw.h:516
franka_hw::FrankaHW::write
virtual void write(const ros::Time &time, const ros::Duration &period) override
Writes data to the franka robot.
Definition: franka_hw.cpp:385
franka_hw::FrankaHW::setupJointStateInterface
virtual void setupJointStateInterface(franka::RobotState &robot_state)
Configures and registers the joint state interface in ros_control.
Definition: franka_hw.cpp:395
franka_hw::FrankaHW::effort_joint_command_ros_
franka::Torques effort_joint_command_ros_
Definition: franka_hw.h:519
franka_hw::FrankaHW::effort_joint_interface_
hardware_interface::EffortJointInterface effort_joint_interface_
Definition: franka_hw.h:496
franka_hw::FrankaHW::arm_id_
std::string arm_id_
Definition: franka_hw.h:528
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
franka_hw::partiallyClaimsArmJoints
bool partiallyClaimsArmJoints(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
Definition: resource_helpers.cpp:187
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
franka_combinable_hw.h
franka_hw::FrankaHW::initRobot
virtual void initRobot()
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
Definition: franka_hw.cpp:546
franka_hw::FrankaHW::run_function_
std::function< void(franka::Robot &, Callback)> run_function_
Definition: franka_hw.h:541
franka_hw::FrankaHW::connect
virtual void connect()
Create a libfranka robot, connecting the hardware class to the master controller.
Definition: franka_hw.cpp:179
franka_hw::FrankaCombinableHW::initRobot
void initRobot() override
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
Definition: franka_combinable_hw.cpp:41
class_list_macros.h
franka_hw::FrankaHW::effort_joint_command_libfranka_
franka::Torques effort_joint_command_libfranka_
Definition: franka_hw.h:512
franka_hw::FrankaHW::checkJointLimits
virtual void checkJointLimits()
Checks the proximity of each joint to its joint position limits and prints a warning whenever a joint...
Definition: franka_hw.cpp:334
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
joint_command_interface.h
hardware_interface::RobotHW
franka_hw::FrankaHW::robot_mutex_
std::mutex robot_mutex_
Definition: franka_hw.h:523
franka_hw::FrankaCombinableHW::setRunFunction
bool setRunFunction(const ControlMode &requested_control_mode, bool limit_rate, double cutoff_frequency, franka::ControllerMode internal_controller) override
Configures the run function which is used as libfranka control callback based on the requested contro...
Definition: franka_combinable_hw.cpp:246
franka_hw::FrankaHW::libfranka_cmd_mutex_
std::mutex libfranka_cmd_mutex_
Definition: franka_hw.h:509
franka_hw::setupServices
void setupServices(franka::Robot &robot, std::mutex &robot_mutex, ros::NodeHandle &node_handle, ServiceContainer &services)
Sets up all services relevant for a libfranka robot inside a service container.
Definition: services.cpp:9
franka_hw::FrankaCombinableHW::controlLoop
void controlLoop()
Definition: franka_combinable_hw.cpp:52
franka_hw::FrankaCombinableHW::has_error_pub_
ros::Publisher has_error_pub_
Definition: franka_combinable_hw.h:188
franka_hw::FrankaHW::robot_state_ros_
franka::RobotState robot_state_ros_
Definition: franka_hw.h:507
franka_hw::FrankaHW::connected
virtual bool connected()
Checks whether the hardware class is connected to a robot.
Definition: franka_hw.cpp:204
franka_hw::FrankaHW::robot_
std::unique_ptr< franka::Robot > robot_
Definition: franka_hw.h:524
franka_hw::ArmClaimedMap
std::map< std::string, ResourceClaims > ArmClaimedMap
Definition: resource_helpers.h:26
franka_hw::FrankaCombinableHW::disconnect
bool disconnect() override
Tries to disconnect the hardware class from the robot, freeing it for e.g.
Definition: franka_combinable_hw.cpp:154
franka_hw::ResourceWithClaimsMap
std::map< std::string, std::vector< std::vector< std::string > >> ResourceWithClaimsMap
Definition: resource_helpers.h:16
franka_hw::FrankaHW::disconnect
virtual bool disconnect()
Tries to disconnect the hardware class from the robot, freeing it for e.g.
Definition: franka_hw.cpp:194
franka_hw::FrankaHW::enforceLimits
virtual void enforceLimits(const ros::Duration &period)
Enforces limits on position, velocity, and torque level.
Definition: franka_hw.cpp:245
franka_hw::FrankaHW::robot_state_libfranka_
franka::RobotState robot_state_libfranka_
Definition: franka_hw.h:506
franka_hw::FrankaCombinableHW::robot_hw_nh_
ros::NodeHandle robot_hw_nh_
Definition: franka_combinable_hw.h:191
franka_hw::FrankaCombinableHW::initROSInterfaces
void initROSInterfaces(ros::NodeHandle &robot_hw_nh) override
Initializes the class in terms of ros_control interfaces.
Definition: franka_combinable_hw.cpp:26
franka_hw::FrankaCombinableHW::hasError
bool hasError() const noexcept
Getter for the error flag of the class.
Definition: franka_combinable_hw.cpp:226
franka_hw::FrankaHW::init
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
Definition: franka_hw.cpp:59
ros::Time
franka_hw::FrankaHW::setupFrankaStateInterface
virtual void setupFrankaStateInterface(franka::RobotState &robot_state)
Configures and registers the state interface offering the full franka::RobotState in ros_control.
Definition: franka_hw.cpp:404
services.h
franka_hw::FrankaCombinableHW::has_error_
std::atomic_bool has_error_
Definition: franka_combinable_hw.h:187
franka_hw
Definition: control_mode.h:8
franka_hw::FrankaCombinableHW::recovery_action_server_
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > recovery_action_server_
Definition: franka_combinable_hw.h:186
franka_hw::FrankaHW::read
virtual void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the franka robot.
Definition: franka_hw.cpp:379
franka_hw::hasTrajectoryClaim
bool hasTrajectoryClaim(const ArmClaimedMap &arm_claim_map, const std::string &arm_id)
Definition: resource_helpers.cpp:206
franka_hw::FrankaCombinableHW::setupServicesAndActionServers
void setupServicesAndActionServers(ros::NodeHandle &node_handle)
Definition: franka_combinable_hw.cpp:108
ROS_ERROR
#define ROS_ERROR(...)
franka_hw::FrankaCombinableHW::control_loop_thread_
std::unique_ptr< std::thread > control_loop_thread_
Definition: franka_combinable_hw.h:183
franka_hw::FrankaHW::initialized_
bool initialized_
Definition: franka_hw.h:534
franka_hw::FrankaCombinableHW::write
void write(const ros::Time &, const ros::Duration &period) override
Writes data to the franka robot.
Definition: franka_combinable_hw.cpp:203
franka_hw::getResourceMap
ResourceWithClaimsMap getResourceMap(const std::list< hardware_interface::ControllerInfo > &info)
Definition: resource_helpers.cpp:23
franka_hw::FrankaHW::ros_state_mutex_
std::mutex ros_state_mutex_
Definition: franka_hw.h:505
franka_hw::FrankaHW::Callback
std::function< bool(const franka::RobotState &, franka::Duration)> Callback
Definition: franka_hw.h:311
franka_hw::FrankaCombinableHW::error_recovered_
std::atomic_bool error_recovered_
Definition: franka_combinable_hw.h:189
ROS_INFO
#define ROS_INFO(...)
franka_hw::hasConflictingMultiClaim
bool hasConflictingMultiClaim(const ResourceWithClaimsMap &resource_map)
Definition: resource_helpers.cpp:138
franka_hw::FrankaHW::robot
virtual franka::Robot & robot() const
Getter for the libfranka robot instance.
Definition: franka_hw.cpp:369
ros::Duration
franka_hw::FrankaHW::controller_active_
std::atomic_bool controller_active_
Definition: franka_hw.h:535
franka_hw::FrankaHW::effort_joint_limit_interface_
joint_limits_interface::EffortJointSoftLimitsInterface effort_joint_limit_interface_
Definition: franka_hw.h:502
franka_hw::ControlMode::JointTorque
@ JointTorque
franka_hw::FrankaCombinableHW::checkForConflict
bool checkForConflict(const std::list< hardware_interface::ControllerInfo > &info) const override
Checks whether a requested controller can be run, based on the resources and interfaces it claims.
Definition: franka_combinable_hw.cpp:173
franka_hw::FrankaCombinableHW::resetError
void resetError()
Recovers the libfranka robot, resets the error flag and publishes the error state.
Definition: franka_combinable_hw.cpp:230
ROS_DEBUG_THROTTLE
#define ROS_DEBUG_THROTTLE(period,...)
ros::NodeHandle
franka_hw::FrankaCombinableHW::control
void control(const std::function< bool(const ros::Time &, const ros::Duration &)> &ros_callback=[](const ros::Time &, const ros::Duration &) { return true;}) override
Runs the currently active controller in a realtime loop.
Definition: franka_combinable_hw.cpp:164
ros::Time::now
static Time now()
franka_hw::FrankaCombinableHW::triggerError
void triggerError()
Triggers a stop of the controlLoop.
Definition: franka_combinable_hw.cpp:221


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:21