-
Notifications
You must be signed in to change notification settings - Fork 40
Expand file tree
/
Copy pathhardware_interface.hpp
More file actions
151 lines (129 loc) · 4.9 KB
/
hardware_interface.hpp
File metadata and controls
151 lines (129 loc) · 4.9 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
/********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef ROS_ETHERCAT_MODEL_HARDWARE_INTERFACE_H
#define ROS_ETHERCAT_MODEL_HARDWARE_INTERFACE_H
#include <string>
#include <vector>
#include <ros/ros.h>
#include "ros_ethercat_model/command.hpp"
namespace ros_ethercat_model
{
class ActuatorState
{
public:
ActuatorState() :
device_id_(0),
position_(0),
clutch_position_(0),
velocity_(0),
effort_(0),
commanded_effort_(0),
last_commanded_current_(0.0),
last_measured_current_(0.0),
last_commanded_effort_(0.0),
last_measured_effort_(0.0),
max_effort_(0.0),
motor_voltage_(0.0),
flags_(0)
{
}
int device_id_; //!< Position in EtherCAT chain
double position_; //!< The position of the motor (in radians)
double velocity_; //!< The velocity in radians per second
double effort_; //!< Measured effort in Nm
int effort_raw_; //!< Raw adc coming from effort sensor;
double current_; //!< Current in Amps
double commanded_effort_;
double temperature_; //!< Measured motor temperature in degrees C
unsigned int flags_; //!< Motor state
double clutch_position_; //!< Position of output of actuator, distally to the clutch.
double last_commanded_current_; //!< Current computed based on effort specified in ActuatorCommand (in amps)
double last_measured_current_; //!< The measured current (in amps)
double last_commanded_effort_; //!< The torque requested in the previous ActuatorCommand (in Nm)
double last_measured_effort_; //!< The measured torque (in Nm)
double max_effort_; //!< Absolute torque limit for actuator (derived from motor current limit). (in Nm)
double motor_voltage_; //!< Motor voltage (in volts)
};
class ActuatorCommand
{
public:
ActuatorCommand() :
enable_(0),
effort_(0),
effort_command_type_(EffortCommandType::UNSPECIFIED)
{
}
bool enable_; //!< Enable this actuator
double effort_; //!< Effort to apply, unit depends on effort_command_type_ field
EffortCommandType effort_command_type_; //!< Type of effort in effort_ field
void set_effort_command(double effort, EffortCommandType effort_command_type)
{
effort_ = effort;
effort_command_type_ = effort_command_type;
}
};
/*!
* \class Actuator
* The Actuator class provides an interface for the motor controller
*
* The ActuatorCommand class is used to enable the motor and set the commanded
* efforts of the motor (in Nm).
*
* The ActuatorState class reports back on the state of the motor
*/
class Actuator
{
public:
std::string name_;
ActuatorState state_;
ActuatorCommand command_;
};
/*!
* \class CustomHW
* The CustomHW class provides an easy way to add more hardware to the HardwareInterface.
* Inherit from that class to add a new type of hardware, containing the data you want.
* If the hardware doesn't use EtherCAT, constructor and destructor
* should initialize drivers to communicate with hardware and
* read and write functions must be implemented accordingly.
* The read and write functions will be called by RosEthercat functions with same names
*/
class CustomHW
{
public:
virtual ~CustomHW() {}
virtual void read(const ros::Time &time) {}
virtual void write(const ros::Time &time) {}
};
} // namespace ros_ethercat_model
#endif