SchunkCanopenHardwareInterface.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // This file is part of the SCHUNK Canopen Driver suite.
5 //
6 // This program is free software licensed under the LGPL
7 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
8 // You can find a copy of this license in LICENSE folder in the top
9 // directory of the source code.
10 //
11 // © Copyright 2016 SCHUNK GmbH, Lauffen/Neckar Germany
12 // © Copyright 2016 FZI Forschungszentrum Informatik, Karlsruhe, Germany
13 // -- END LICENSE BLOCK ------------------------------------------------
14 
15 //----------------------------------------------------------------------
22 //----------------------------------------------------------------------
23 
24 #ifndef SCHUNK_CANOPEN_HARDWARE_INTERFACE_H_
25 #define SCHUNK_CANOPEN_HARDWARE_INTERFACE_H_
26 
28 
34 #include <ros/ros.h>
35 #include <sensor_msgs/JointState.h>
40 
41 using namespace icl_hardware;
42 using namespace canopen_schunk;
43 
49 {
50 public:
52 
54  virtual void init();
55 
57  virtual void read();
58 
60  virtual void write(ros::Time time, ros::Duration period);
61 
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);
67 
71  bool isFault() {return m_is_fault;}
72 
76  sensor_msgs::JointState getJointMessage();
77 
78 protected:
81 
82  // Interfaces
86 
87  size_t m_num_joints;
88 
89  std::vector<uint8_t> m_node_ids;
90  std::vector<std::string> m_joint_names;
91  std::vector<double> m_joint_positions;
92  std::vector<double> m_joint_velocity;
93  std::vector<double> m_joint_effort;
94  std::vector<double> m_joint_position_commands;
95  std::vector<double> m_joint_position_commands_last;
96 
97  std::vector<bool> m_nodes_in_fault;
98  bool m_is_fault;
99 
101  joint_limits_interface::SoftJointLimits m_joint_soft_limits; // only available through URDF, currently not used.
102 };
103 
104 
105 
106 #endif /*SCHUNK_CANOPEN_HARDWARE_INTERFACE_H_*/
boost::shared_ptr< CanOpenController > m_canopen_controller
hardware_interface::PositionJointInterface m_position_joint_interface
hardware_interface::JointStateInterface m_joint_state_interface
joint_limits_interface::JointLimits m_joint_limits
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
This class defines a ros-control hardware interface.


schunk_canopen_driver
Author(s): Felix Mauch , Georg Heppner
autogenerated on Mon Jun 10 2019 15:07:49