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
#define ROS_FATAL(...)
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > recovery_action_server_
void initRobot() override
Uses the robot_ip_ to connect to the robot via libfranka and loads the libfranka model.
std::unique_ptr< std::thread > control_loop_thread_
void triggerError()
Triggers a stop of the controlLoop.
A hardware class for a Panda robot based on the ros_control framework.
std::string getArmID() const noexcept
Getter method for the arm_id which is used to distinguish between multiple instances of FrankaCombina...
void initROSInterfaces(ros::NodeHandle &robot_hw_nh) override
Initializes the class in terms of ros_control interfaces.
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
T libfrankaUpdateCallback(const T &command, const franka::RobotState &robot_state, franka::Duration time_step)
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...
bool hasError() const noexcept
Getter for the error flag of the class.
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Initializes the FrankaHW class to be fully operational.
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.
void read(const ros::Time &, const ros::Duration &) override
Reads data from the franka robot.
std::mutex libfranka_cmd_mutex_
Definition: franka_hw.h:509
franka::RobotState robot_state_libfranka_
Definition: franka_hw.h:506
void resetError()
Recovers the libfranka robot, resets the error flag and publishes the error state.
void setupServicesAndActionServers(ros::NodeHandle &node_handle)
std::atomic_bool controller_active_
Definition: franka_hw.h:535
FrankaCombinableHW()
Creates an instance of FrankaCombinableHW.
void connect() override
Create a libfranka robot, connecting the hardware class to the master controller. ...
void write(const ros::Time &, const ros::Duration &period) override
Writes data to the franka robot.
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...
This class wraps the functionality of libfranka for controlling Panda robots into the ros_control fra...
Definition: franka_hw.h:38
bool disconnect() override
Tries to disconnect the hardware class from the robot, freeing it for e.g.
std::unique_ptr< ServiceContainer > services_
bool controllerNeedsReset() const noexcept
Returns whether the controller needs to be reset e.g.
Torques MotionFinished(Torques command) noexcept
std::mutex libfranka_state_mutex_
Definition: franka_hw.h:504
static bool commandHasNaN(const franka::Torques &command)
Checks a command for NaN values.
Definition: franka_hw.cpp:581


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 03:05:56