24 #ifndef SCHUNK_CANOPEN_HARDWARE_INTERFACE_H_ 25 #define SCHUNK_CANOPEN_HARDWARE_INTERFACE_H_ 35 #include <sensor_msgs/JointState.h> 42 using namespace canopen_schunk;
62 virtual bool prepareSwitch(
63 const std::list<hardware_interface::ControllerInfo> &start_list,
64 const std::list<hardware_interface::ControllerInfo> &stop_list);
65 virtual void doSwitch(
const std::list<hardware_interface::ControllerInfo>&start_list,
66 const std::list<hardware_interface::ControllerInfo>&stop_list);
76 sensor_msgs::JointState getJointMessage();
ros::NodeHandle m_node_handle
boost::shared_ptr< CanOpenController > m_canopen_controller
std::vector< std::string > m_joint_names
hardware_interface::PositionJointInterface m_position_joint_interface
hardware_interface::JointStateInterface m_joint_state_interface
std::vector< double > m_joint_effort
joint_limits_interface::JointLimits m_joint_limits
std::vector< double > m_joint_velocity
joint_limits_interface::SoftJointLimits m_joint_soft_limits
bool isFault()
Returns true, when at least one node in the hardware is in a fault state.
joint_limits_interface::PositionJointSoftLimitsInterface m_jnt_limits_interface
std::vector< bool > m_nodes_in_fault
This class defines a ros-control hardware interface.
std::vector< double > m_joint_position_commands_last
std::vector< double > m_joint_positions
std::vector< double > m_joint_position_commands
std::vector< uint8_t > m_node_ids