franka_combined_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 
7 #include <franka_msgs/ErrorRecoveryAction.h>
8 
10 #include <ros/node_handle.h>
11 #include <ros/time.h>
12 
13 #include <memory>
14 
15 namespace franka_hw {
16 
18  public:
24 
25  ~FrankaCombinedHW() override = default; // NOLINT (clang-analyzer-optin.cplusplus.VirtualCall)
26 
36  bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
37 
44  void read(const ros::Time& time, const ros::Duration& period) override;
45 
51  bool controllerNeedsReset();
52 
53  protected:
54  std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
56 
57  private:
58  void handleError();
59  bool hasError();
60  void triggerError();
61  bool is_recovering_{false};
62 };
63 
64 } // namespace franka_hw
~FrankaCombinedHW() override=default
bool controllerNeedsReset()
Checks whether the controller needs to be reset.
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...
FrankaCombinedHW()
Creates an instance of CombinedFrankaHW.
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > combined_recovery_action_server_
void read(const ros::Time &time, const ros::Duration &period) override
Reads data from the robot HW.


franka_hw
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:05