joint_velocity_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * Copyright (c) 2012, hiDOF, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef EFFORT_CONTROLLERS__JOINT_VELOCITY_CONTROLLER_H
37 #define EFFORT_CONTROLLERS__JOINT_VELOCITY_CONTROLLER_H
38 
62 #include <ros/node_handle.h>
63 #include <boost/thread/condition.hpp>
64 #include <boost/scoped_ptr.hpp>
67 #include <control_msgs/JointControllerState.h>
68 #include <std_msgs/Float64.h>
69 #include <control_toolbox/pid.h>
71 
72 namespace effort_controllers
73 {
74 
75 class JointVelocityController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
76 {
77 public:
78 
81 
82  bool init(hardware_interface::EffortJointInterface *robot, const std::string &joint_name, const control_toolbox::Pid &pid);
83 
98 
104  void setCommand(double cmd);
105 
109  void getCommand(double & cmd);
110 
116  void starting(const ros::Time& time);
117 
121  void update(const ros::Time& time, const ros::Duration& period);
122 
126  void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
127 
131  void getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup);
132 
136  void printDebug();
137 
141  void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup = false);
142 
146  std::string getJointName();
147 
149  double command_;
151 private:
155  //friend class JointVelocityControllerNode; // what is this for??
156 
157  boost::scoped_ptr<
159  control_msgs::JointControllerState> > controller_state_publisher_ ;
160 
162 
166  void setCommandCB(const std_msgs::Float64ConstPtr& msg);
167 };
168 
169 } // namespace
170 
171 #endif
d
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup=false)
Get the PID parameters.
string cmd
void starting(const ros::Time &time)
This is called from within the realtime thread just before the first call to update.
void setCommand(double cmd)
Give set velocity of the joint for next update: revolute (angle) and prismatic (velocity) ...
void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Callback from /command subscriber for setpoint.
std::string getJointName()
Get the name of the joint this controller uses.
bool init(hardware_interface::EffortJointInterface *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get the PID parameters.
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
void getCommand(double &cmd)
Get latest velocity command to the joint: revolute (angle) and prismatic (velocity).


effort_controllers
Author(s): Vijay Pradeep
autogenerated on Thu Apr 11 2019 03:08:20