/
joint_position_controller.h
202 lines (167 loc) · 6.61 KB
/
joint_position_controller.h
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
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* Copyright (c) 2012, hiDOF, Inc.
* Copyright (c) 2013, University of Colorado, Boulder
* 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.
*********************************************************************/
/*
Author: Dave Coleman
Contributors: Jonathan Bohren, Wim Meeussen, Vijay Pradeep
Desc: Velocity-based position controller using basic PID loop
*/
#ifndef VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
#define VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
/**
@class velocity_controllers::JointPositionController
@brief Joint Position Controller
This class controls positon using a pid loop.
@section ROS ROS interface
@param type Must be "velocity_controllers::JointPositionController"
@param joint Name of the joint to control.
@param pid Contains the gains for the PID loop around position. See: control_toolbox::Pid
Subscribes to:
- @b command (std_msgs::Float64) : The joint position to achieve.
Publishes:
- @b state (control_msgs::JointControllerState) :
Current state of the controller, including pid error and gains.
*/
#include <ros/node_handle.h>
#include <urdf/model.h>
#include <control_toolbox/pid.h>
#include <boost/scoped_ptr.hpp>
#include <boost/thread/condition.hpp>
#include <realtime_tools/realtime_publisher.h>
#include <hardware_interface/joint_command_interface.h>
#include <controller_interface/controller.h>
#include <control_msgs/JointControllerState.h>
#include <std_msgs/Float64.h>
#include <control_msgs/JointControllerState.h>
#include <realtime_tools/realtime_buffer.h>
namespace velocity_controllers
{
class JointPositionController: public controller_interface::Controller<hardware_interface::VelocityJointInterface>
{
public:
/**
* \brief Store position and velocity command in struct to allow easier realtime buffer usage
*/
struct Commands
{
double position_; // Last commanded position
double velocity_; // Last commanded velocity
bool has_velocity_; // false if no velocity command has been specified
};
JointPositionController();
~JointPositionController();
/** \brief The init function is called to initialize the controller from a
* non-realtime thread with a pointer to the hardware interface, itself,
* instead of a pointer to a RobotHW.
*
* \param robot The specific hardware interface used by this controller.
*
* \param n A NodeHandle in the namespace from which the controller
* should read its configuration, and where it should set up its ROS
* interface.
*
* \returns True if initialization was successful and the controller
* is ready to be started.
*/
bool init(hardware_interface::VelocityJointInterface *robot, ros::NodeHandle &n);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
*
* \param command
*/
void setCommand(double pos_target);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
* Also supports a target velocity
*
* \param pos_target - position setpoint
* \param vel_target - velocity setpoint
*/
void setCommand(double pos_target, double vel_target);
/** \brief This is called from within the realtime thread just before the
* first call to \ref update
*
* \param time The current time
*/
void starting(const ros::Time& time);
/*!
* \brief Issues commands to the joint. Should be called at regular intervals
*/
void update(const ros::Time& time, const ros::Duration& period);
/**
* \brief Get the PID parameters
*/
void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
/**
* \brief Print debug info to console
*/
void printDebug();
/**
* \brief Get the PID parameters
*/
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
/**
* \brief Get the name of the joint this controller uses
*/
std::string getJointName();
/**
* \brief Get the current position of the joint
* \return current position
*/
double getPosition();
hardware_interface::JointHandle joint_;
boost::shared_ptr<const urdf::Joint> joint_urdf_;
realtime_tools::RealtimeBuffer<Commands> command_;
Commands command_struct_; // pre-allocated memory that is re-used to set the realtime buffer
private:
int loop_count_;
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
boost::scoped_ptr<
realtime_tools::RealtimePublisher<
control_msgs::JointControllerState> > controller_state_publisher_ ;
ros::Subscriber sub_command_;
/**
* \brief Callback from /command subscriber for setpoint
*/
void setCommandCB(const std_msgs::Float64ConstPtr& msg);
/**
* \brief Check that the command is within the hard limits of the joint. Checks for joint
* type first. Sets command to limit if out of bounds.
* \param command - the input to test
*/
void enforceJointLimits(double &command);
};
} // namespace
#endif