franka_combinable_hw.h
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
3 #pragma once
4 
5 #include <atomic>
6 #include <functional>
7 #include <memory>
8 #include <string>
9 #include <thread>
10 
11 #include <franka/exception.h>
12 #include <franka/robot_state.h>
13 
15 #include <franka_hw/franka_hw.h>
16 #include <franka_hw/services.h>
17 #include <franka_msgs/ErrorRecoveryAction.h>
18 #include <ros/ros.h>
19 
20 namespace franka_hw {
21 
30 class FrankaCombinableHW : public FrankaHW {
31  public:
36 
37  /*
38  * Initializes the hardware class. That includes parsing parameters, connecting to the robot,
39  * setting up ros_control interfaces ans ROS services and actions.
40  *
41  * @param[in] root_nh A node handle in the root namespace of the control node.
42  * @param[in] robot_hw_nh A node handle in the namespace of the robot hardware.
43  * @return True if successful, false otherwise.
44  */
45  bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
46 
55  void initROSInterfaces(ros::NodeHandle& robot_hw_nh) override;
56 
61  void connect() override;
62 
68  bool disconnect() override;
69 
81  void control(const std::function<bool(const ros::Time&, const ros::Duration&)>&
82  ros_callback = // NOLINT (google-default-arguments)
83  [](const ros::Time&, const ros::Duration&) {
84  return true;
85  }) override; // NOLINT (google-default-arguments)
86 
95  bool checkForConflict(const std::list<hardware_interface::ControllerInfo>& info) const override;
96 
103  void read(const ros::Time& /*time*/, const ros::Duration& /*period*/) override;
104 
111  void write(const ros::Time& /*time*/, const ros::Duration& period) override;
112 
119  std::string getArmID() const noexcept;
120 
125  void triggerError();
126 
132  bool hasError() const noexcept;
133 
137  void resetError();
138 
144  bool controllerNeedsReset() const noexcept;
145 
146  private:
147  template <typename T>
148  T libfrankaUpdateCallback(const T& command,
149  const franka::RobotState& robot_state,
150  franka::Duration time_step) {
151  if (commandHasNaN(command)) {
152  std::string error_message = "FrankaCombinableHW: Got NaN value in command!";
153  ROS_FATAL("%s", error_message.c_str());
154  throw std::invalid_argument(error_message);
155  }
157  {
158  std::lock_guard<std::mutex> state_lock(libfranka_state_mutex_);
159  robot_state_libfranka_ = robot_state;
160  }
161 
162  std::lock_guard<std::mutex> command_lock(libfranka_cmd_mutex_);
163  T current_cmd = command;
164  if (has_error_ || !controller_active_) {
165  return franka::MotionFinished(current_cmd);
166  }
167  return current_cmd;
168  }
169 
170  void publishErrorState(bool error);
171 
173 
174  void initRobot() override;
175 
176  bool setRunFunction(const ControlMode& requested_control_mode,
177  bool limit_rate,
178  double cutoff_frequency,
179  franka::ControllerMode internal_controller) override;
180 
181  void controlLoop();
182 
183  std::unique_ptr<std::thread> control_loop_thread_;
184  std::unique_ptr<ServiceContainer> services_;
185  std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
187  std::atomic_bool has_error_{false};
189  std::atomic_bool error_recovered_{false};
190  std::atomic_bool controller_needs_reset_{false};
192 };
193 
194 } // namespace franka_hw
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
ros::Publisher
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
franka_hw::ControlMode
ControlMode
Definition: control_mode.h:10
franka_hw::FrankaHW
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
Definition: franka_hw.h:38
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
ros.h
command
ROSLIB_DECL std::string command(const std::string &cmd)
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::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
simple_action_server.h
franka_hw::FrankaCombinableHW::libfrankaUpdateCallback
T libfrankaUpdateCallback(const T &command, const franka::RobotState &robot_state, franka::Duration time_step)
Definition: franka_combinable_hw.h:148
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
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
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::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::FrankaCombinableHW::FrankaCombinableHW
FrankaCombinableHW()
Creates an instance of FrankaCombinableHW.
Definition: franka_combinable_hw.cpp:19
franka_hw.h
franka_hw::FrankaHW::commandHasNaN
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.
Definition: franka_hw.cpp:581
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
ROS_FATAL
#define ROS_FATAL(...)
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
ros::Time
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::FrankaCombinableHW::setupServicesAndActionServers
void setupServicesAndActionServers(ros::NodeHandle &node_handle)
Definition: franka_combinable_hw.cpp:108
franka_hw::FrankaCombinableHW::control_loop_thread_
std::unique_ptr< std::thread > control_loop_thread_
Definition: franka_combinable_hw.h:183
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::FrankaCombinableHW::error_recovered_
std::atomic_bool error_recovered_
Definition: franka_combinable_hw.h:189
ros::Duration
franka_hw::FrankaHW::controller_active_
std::atomic_bool controller_active_
Definition: franka_hw.h:535
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::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
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