Go to the documentation of this file.
32 #ifndef SCHUNK_SVH_HARDWARE_INTERFACE_H_
33 #define SCHUNK_SVH_HARDWARE_INTERFACE_H_
45 #include <sensor_msgs/JointState.h>
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);
86 std::shared_ptr<SVHWrapper>
m_svh;
hardware_interface::PositionJointInterface m_position_joint_interface
std::vector< double > m_joint_velocity
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
std::vector< std::string > m_channel_names
joint_limits_interface::JointLimits m_joint_limits
SVHRosControlHWInterface()
bool isFault()
Returns true, when at least one node in the hardware is in a fault state.
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
Initialize the hardware interface.
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
~SVHRosControlHWInterface()
std::vector< uint8_t > m_node_ids
std::shared_ptr< SVHWrapper > m_svh
Handle to the SVH finger manager for library access.
virtual void read(const ros::Time &time, const ros::Duration &period)
Read the state from the robot hardware.
hardware_interface::JointStateInterface m_joint_state_interface
This class defines a ros-control hardware interface.
joint_limits_interface::SoftJointLimits m_joint_soft_limits
ros::NodeHandle m_node_handle
Creates a joint_state message from the current joint angles and returns it.
std::vector< double > m_joint_position_commands
virtual void write(const ros::Time &time, const ros::Duration &period)
write the command to the robot hardware.
std::vector< double > m_joint_effort
std::vector< double > m_joint_positions
schunk_svh_driver
Author(s): Georg Heppner
, Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55