NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
dummyinterface.h
1 // NimbRo-OP robot hardware interface (dummy)
2 // Author: Philipp Allgeuer <pallgeuer@ais.uni-bonn.de>
3 
4 // Ensure header is only included once
5 #ifndef NOP_DUMMY_INTERFACE_H
6 #define NOP_DUMMY_INTERFACE_H
7 
8 // Includes
9 #include <nimbro_op_interface/robotinterface.h>
10 #include <boost/circular_buffer.hpp>
11 #include <config_server/parameter.h>
12 
13 // NimbRo-OP interface namespace
14 namespace nimbro_op_interface
15 {
16  // DummyInterface class
17  class DummyInterface : public nimbro_op_interface::RobotInterface
18  {
19  public:
20  // Constructor/destructor
21  DummyInterface();
22  virtual ~DummyInterface();
23 
24  // Virtual function overrides
25  virtual bool sendJointTargets();
26  virtual bool readJointStates();
27 
28  protected:
29  // Virtual functions to override attempts to connect to the CM730
30  virtual bool initCM730() { return true; }
31  virtual int readFeedbackData(bool onlyTryCM730);
32  virtual bool syncWriteJointTargets(size_t numDevices, const uint8_t* data);
33  virtual bool syncWriteTorqueEnable(size_t numDevices, const uint8_t* data) { return true; }
34  virtual bool syncWriteTorqueLimit(size_t numDevices, const uint8_t* data) { return true; }
35  virtual bool useModel() const { return m_useModel(); }
36 
37  private:
38  // Constants
39  const std::string CONFIG_PARAM_PATH;
40 
41  // Config server parameters
42  config_server::Parameter<bool> m_useModel;
43  config_server::Parameter<bool> m_addDelay;
44  config_server::Parameter<bool> m_noiseEnable;
45  config_server::Parameter<float> m_noiseMagnitude;
46  config_server::Parameter<bool> m_buttonPress0;
47  config_server::Parameter<bool> m_buttonPress1;
48  config_server::Parameter<bool> m_buttonPress2;
49  config_server::Parameter<int> m_fakeTemperature;
50  config_server::Parameter<float> m_fakeIMUGyroX;
51  config_server::Parameter<float> m_fakeIMUGyroY;
52  config_server::Parameter<float> m_fakeIMUGyroZ;
53  config_server::Parameter<float> m_fakeIMUAccX;
54  config_server::Parameter<float> m_fakeIMUAccY;
55  config_server::Parameter<float> m_fakeIMUAccZ;
56  config_server::Parameter<float> m_fakeIMUMagX;
57  config_server::Parameter<float> m_fakeIMUMagY;
58  config_server::Parameter<float> m_fakeIMUMagZ;
59  config_server::Parameter<bool> m_fakeAttEnable;
60  config_server::Parameter<float> m_fakeAttFusedX;
61  config_server::Parameter<float> m_fakeAttFusedY;
62  config_server::Parameter<float> m_fakeAttFusedZ;
63  config_server::Parameter<bool> m_fakeAttFusedHemi;
64 
65  // Config server callbacks
66  void updateUseModel();
67 
68  // Misc flags
69  bool m_calledReadFeedback;
70 
71  // Joint command data buffer
72  typedef std::map<uint8_t, JointCmdSyncWriteData> JointCmd;
73  boost::circular_buffer<JointCmd> m_jointCmdBuf;
74  };
75 }
76 
77 #endif
78 
79 // EOF
Real robot interface.
Definition: robotinterface.h:74