SVHRosControlHWInterface.h
Go to the documentation of this file.
1 //
3 // © Copyright 2022 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
4 // © Copyright 2022 FZI Forschungszentrum Informatik, Karlsruhe, Germany
5 //
6 // This file is part of the Schunk SVH Driver.
7 //
8 // The Schunk SVH Driver is free software: you can redistribute it and/or
9 // modify it under the terms of the GNU General Public License as published by
10 // the Free Software Foundation, either version 3 of the License, or (at your
11 // option) any later version.
12 //
13 // The Schunk SVH Driver is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
16 // Public License for more details.
17 //
18 // You should have received a copy of the GNU General Public License along with
19 // the Schunk SVH Driver. If not, see <https://www.gnu.org/licenses/>.
20 //
22 
23 //----------------------------------------------------------------------
30 //----------------------------------------------------------------------
31 
32 #ifndef SCHUNK_SVH_HARDWARE_INTERFACE_H_
33 #define SCHUNK_SVH_HARDWARE_INTERFACE_H_
34 
35 // Driver Specific things
36 #include "SVHWrapper.h"
37 
43 #include <memory>
44 #include <ros/ros.h>
45 #include <sensor_msgs/JointState.h>
46 
52 {
53 public:
56 
58  virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh);
59  // virtual void init();
60 
62  virtual void read(const ros::Time& time, const ros::Duration& period);
63 
65  virtual void write(const ros::Time& time, const ros::Duration& period);
66 
67  bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
68  const std::list<hardware_interface::ControllerInfo>& stop_list);
69  void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
70  const std::list<hardware_interface::ControllerInfo>& stop_list);
71 
72 
73  bool isEnabled() const;
77  bool isFault() { return m_is_fault; }
81  // sensor_msgs::JointState getJointMessage();
82 
83 protected:
86  std::shared_ptr<SVHWrapper> m_svh;
87 
88  // Interfaces
91 
92  size_t m_num_joints;
93 
94  std::vector<uint8_t> m_node_ids;
95  std::vector<std::string> m_channel_names; // Combines prefix with channel_description
96  std::vector<double> m_joint_positions;
97  std::vector<double> m_joint_velocity;
98  std::vector<double> m_joint_effort;
99  std::vector<double> m_joint_position_commands;
100 
102 
105  m_joint_soft_limits; // only available through URDF, currently not used.
106 
107 private:
109 };
110 
111 
112 #endif /*SCHUNK_SVH_HARDWARE_INTERFACE_H_*/
SVHRosControlHWInterface::m_position_joint_interface
hardware_interface::PositionJointInterface m_position_joint_interface
Definition: SVHRosControlHWInterface.h:90
SVHRosControlHWInterface::m_joint_velocity
std::vector< double > m_joint_velocity
Definition: SVHRosControlHWInterface.h:97
SVHWrapper.h
SVHRosControlHWInterface::doSwitch
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
Definition: SVHRosControlHWInterface.cpp:184
joint_limits_interface::JointLimits
SVHRosControlHWInterface::m_channel_names
std::vector< std::string > m_channel_names
Definition: SVHRosControlHWInterface.h:95
hardware_interface::JointStateInterface
ros.h
SVHRosControlHWInterface::m_joint_limits
joint_limits_interface::JointLimits m_joint_limits
Definition: SVHRosControlHWInterface.h:103
SVHRosControlHWInterface::m_hardware_ready
bool m_hardware_ready
Definition: SVHRosControlHWInterface.h:108
joint_limits.h
controller_manager.h
SVHRosControlHWInterface::SVHRosControlHWInterface
SVHRosControlHWInterface()
Definition: SVHRosControlHWInterface.cpp:49
SVHRosControlHWInterface::isFault
bool isFault()
Returns true, when at least one node in the hardware is in a fault state.
Definition: SVHRosControlHWInterface.h:77
SVHRosControlHWInterface::init
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
Initialize the hardware interface.
Definition: SVHRosControlHWInterface.cpp:54
SVHRosControlHWInterface::prepareSwitch
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
Definition: SVHRosControlHWInterface.cpp:177
SVHRosControlHWInterface::~SVHRosControlHWInterface
~SVHRosControlHWInterface()
Definition: SVHRosControlHWInterface.cpp:51
joint_command_interface.h
hardware_interface::RobotHW
SVHRosControlHWInterface::m_node_ids
std::vector< uint8_t > m_node_ids
Definition: SVHRosControlHWInterface.h:94
SVHRosControlHWInterface::m_is_fault
bool m_is_fault
Definition: SVHRosControlHWInterface.h:101
SVHRosControlHWInterface::m_svh
std::shared_ptr< SVHWrapper > m_svh
Handle to the SVH finger manager for library access.
Definition: SVHRosControlHWInterface.h:86
SVHRosControlHWInterface::read
virtual void read(const ros::Time &time, const ros::Duration &period)
Read the state from the robot hardware.
Definition: SVHRosControlHWInterface.cpp:104
SVHRosControlHWInterface::m_joint_state_interface
hardware_interface::JointStateInterface m_joint_state_interface
Definition: SVHRosControlHWInterface.h:89
joint_state_interface.h
SVHRosControlHWInterface
This class defines a ros-control hardware interface.
Definition: SVHRosControlHWInterface.h:51
ros::Time
SVHRosControlHWInterface::m_joint_soft_limits
joint_limits_interface::SoftJointLimits m_joint_soft_limits
Definition: SVHRosControlHWInterface.h:105
robot_hw.h
SVHRosControlHWInterface::m_node_handle
ros::NodeHandle m_node_handle
Creates a joint_state message from the current joint angles and returns it.
Definition: SVHRosControlHWInterface.h:84
SVHRosControlHWInterface::m_joint_position_commands
std::vector< double > m_joint_position_commands
Definition: SVHRosControlHWInterface.h:99
SVHRosControlHWInterface::write
virtual void write(const ros::Time &time, const ros::Duration &period)
write the command to the robot hardware.
Definition: SVHRosControlHWInterface.cpp:146
SVHRosControlHWInterface::m_num_joints
size_t m_num_joints
Definition: SVHRosControlHWInterface.h:92
SVHRosControlHWInterface::isEnabled
bool isEnabled() const
Definition: SVHRosControlHWInterface.cpp:191
hardware_interface::PositionJointInterface
joint_limits_interface::SoftJointLimits
ros::Duration
SVHRosControlHWInterface::m_joint_effort
std::vector< double > m_joint_effort
Definition: SVHRosControlHWInterface.h:98
SVHRosControlHWInterface::m_joint_positions
std::vector< double > m_joint_positions
Definition: SVHRosControlHWInterface.h:96
ros::NodeHandle


schunk_svh_driver
Author(s): Georg Heppner , Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55