franka_combined_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 <algorithm>
6 #include <memory>
7 
9 #include <ros/node_handle.h>
10 #include <ros/time.h>
11 #include <std_srvs/Trigger.h>
12 
14 #include <franka_hw/franka_hw.h>
15 #include <franka_msgs/ErrorRecoveryAction.h>
16 
17 namespace franka_hw {
18 
20 
22  bool success = CombinedRobotHW::init(root_nh, robot_hw_nh);
23  // Error recovery server for all FrankaHWs
25  std::make_unique<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>(
26  robot_hw_nh, "error_recovery",
27  [&](const franka_msgs::ErrorRecoveryGoalConstPtr&) {
28  try {
29  is_recovering_ = true;
30  for (const auto& robot_hw : robot_hw_list_) {
31  auto* franka_combinable_hw_ptr =
32  dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
33  if (franka_combinable_hw_ptr != nullptr && franka_combinable_hw_ptr->connected()) {
34  franka_combinable_hw_ptr->resetError();
35  } else {
36  ROS_ERROR("FrankaCombinedHW: failed to reset error. Is the robot connected?");
37  is_recovering_ = false;
39  franka_msgs::ErrorRecoveryResult(),
40  "dynamic_cast from RobotHW to FrankaCombinableHW failed");
41  return;
42  }
43  }
44  is_recovering_ = false;
45  combined_recovery_action_server_->setSucceeded();
46  } catch (const franka::Exception& ex) {
47  is_recovering_ = false;
48  combined_recovery_action_server_->setAborted(franka_msgs::ErrorRecoveryResult(),
49  ex.what());
50  }
51  },
52  false);
54 
56  robot_hw_nh.advertiseService<std_srvs::Trigger::Request, std_srvs::Trigger::Response>(
57  "connect",
58  [this](std_srvs::Trigger::Request& request,
59  std_srvs::Trigger::Response& response) -> bool {
60  try {
61  connect();
62  ROS_INFO("FrankaCombinedHW: successfully connected robots.");
63  response.success = 1u;
64  response.message = "";
65  } catch (const std::exception& e) {
66  ROS_INFO("Combined: exception %s", e.what());
67  response.success = 0u;
68  response.message =
69  "FrankaCombinedHW: Failed to connect robot: " + std::string(e.what());
70  }
71  return true;
72  });
73 
75  robot_hw_nh.advertiseService<std_srvs::Trigger::Request, std_srvs::Trigger::Response>(
76  "disconnect",
77  [this](std_srvs::Trigger::Request& request,
78  std_srvs::Trigger::Response& response) -> bool {
79  bool success = disconnect();
80  response.success = success ? 1u : 0u;
81  response.message = success
82  ? "FrankaCombinedHW: Successfully disconnected robots."
83  : "FrankaCombinedHW: Failed to disconnect robots. All active "
84  "controllers must be stopped before you can disconnect.";
85  if (success) {
86  ROS_INFO("%s", response.message.c_str());
87  } else {
88  ROS_ERROR("%s", response.message.c_str());
89  }
90  return true;
91  });
92 
93  return success;
94 }
95 
96 void FrankaCombinedHW::read(const ros::Time& time, const ros::Duration& period) {
97  // Call the read method of the single RobotHW objects.
98  CombinedRobotHW::read(time, period);
99  handleError();
100 }
101 
103  // Check if any of the RobotHW object needs a controller reset
104  bool controller_reset = false;
105  for (const auto& robot_hw : robot_hw_list_) {
106  auto* franka_combinable_hw_ptr = dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
107  if (franka_combinable_hw_ptr != nullptr) {
108  controller_reset = controller_reset || franka_combinable_hw_ptr->controllerNeedsReset();
109  } else {
110  ROS_ERROR("FrankaCombinedHW: dynamic_cast from RobotHW to FrankaCombinableHW failed.");
111  return false;
112  }
113  }
114  return controller_reset;
115 }
116 
118  // Trigger error state of all other RobotHW objects when one of them has a error.
119  if (hasError() && !is_recovering_) {
120  triggerError();
121  }
122 }
123 
125  bool has_error = false;
126  for (const auto& robot_hw : robot_hw_list_) {
127  auto* franka_combinable_hw_ptr = dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
128  if (franka_combinable_hw_ptr != nullptr) {
129  has_error = has_error || franka_combinable_hw_ptr->hasError();
130  } else {
131  ROS_ERROR("FrankaCombinedHW: dynamic_cast from RobotHW to FrankaCombinableHW failed.");
132  return false;
133  }
134  }
135  return has_error;
136 }
137 
139  // Trigger error state of all RobotHW objects.
140  for (const auto& robot_hw : robot_hw_list_) {
141  auto* franka_combinable_hw_ptr = dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
142  if (franka_combinable_hw_ptr != nullptr) {
143  franka_combinable_hw_ptr->triggerError();
144  } else {
145  ROS_ERROR("FrankaCombinedHW: dynamic_cast from RobotHW to FrankaCombinableHW failed.");
146  }
147  }
148 }
149 
151  for (const auto& robot_hw : robot_hw_list_) {
152  auto* franka_combinable_hw_ptr = dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
153  if (franka_combinable_hw_ptr != nullptr && !franka_combinable_hw_ptr->connected()) {
154  franka_combinable_hw_ptr->connect();
155  }
156  }
157 }
158 
160  // Ensure all robots are disconnectable (not running a controller)
161  for (const auto& robot_hw : robot_hw_list_) {
162  auto* franka_combinable_hw_ptr = dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
163  if (franka_combinable_hw_ptr != nullptr && franka_combinable_hw_ptr->controllerActive()) {
164  return false;
165  }
166  }
167 
168  // Only if all robots are in fact disconnectable, disconnecting them.
169  // Fail and abort if any robot cannot be disconnected.
170  for (const auto& robot_hw : robot_hw_list_) {
171  auto* franka_combinable_hw_ptr = dynamic_cast<franka_hw::FrankaCombinableHW*>(robot_hw.get());
172  if (franka_combinable_hw_ptr != nullptr && !franka_combinable_hw_ptr->disconnect()) {
173  return false;
174  }
175  }
176 
177  return true;
178 }
179 
180 } // namespace franka_hw
response
const std::string response
node_handle.h
franka_hw::FrankaCombinedHW::read
void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the robot HW.
Definition: franka_combined_hw.cpp:96
franka_hw::FrankaCombinedHW::disconnect
bool disconnect()
Tries to disconnect on all hardware classes that are of type FrankaCombinableHW.
Definition: franka_combined_hw.cpp:159
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
franka_hw::FrankaCombinedHW::connect_server_
ros::ServiceServer connect_server_
Definition: franka_combined_hw.h:72
franka_hw::FrankaCombinedHW::FrankaCombinedHW
FrankaCombinedHW()
Creates an instance of CombinedFrankaHW.
time.h
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::FrankaCombinedHW::disconnect_server_
ros::ServiceServer disconnect_server_
Definition: franka_combined_hw.h:73
simple_action_server.h
franka_hw::FrankaCombinedHW::controllerNeedsReset
bool controllerNeedsReset()
Checks whether the controller needs to be reset.
Definition: franka_combined_hw.cpp:102
franka_combined_hw.h
franka_combinable_hw.h
franka_hw::FrankaCombinedHW::triggerError
void triggerError()
Definition: franka_combined_hw.cpp:138
combined_robot_hw::CombinedRobotHW::robot_hw_list_
std::vector< hardware_interface::RobotHWSharedPtr > robot_hw_list_
franka_hw::FrankaCombinedHW::combined_recovery_action_server_
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > combined_recovery_action_server_
Definition: franka_combined_hw.h:71
franka_hw::FrankaCombinedHW::init
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
The init function is called to initialize the CombinedFrankaHW from a non-realtime thread.
Definition: franka_combined_hw.cpp:21
franka_hw::FrankaCombinedHW::is_recovering_
bool is_recovering_
Definition: franka_combined_hw.h:78
franka_hw.h
franka_hw::FrankaCombinableHW::hasError
bool hasError() const noexcept
Getter for the error flag of the class.
Definition: franka_combinable_hw.cpp:226
ros::Time
franka_hw
Definition: control_mode.h:8
franka_hw::FrankaCombinedHW::connect
void connect()
Calls connect on all hardware classes that are of type FrankaCombinableHW.
Definition: franka_combined_hw.cpp:150
ROS_ERROR
#define ROS_ERROR(...)
franka_hw::FrankaCombinedHW::hasError
bool hasError()
Checks whether the robots are in error or reflex mode.
Definition: franka_combined_hw.cpp:124
ROS_INFO
#define ROS_INFO(...)
ros::Duration
franka_hw::FrankaCombinedHW::handleError
void handleError()
Definition: franka_combined_hw.cpp:117
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::NodeHandle
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