joint_velocity_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
37 
39 
40 using namespace std;
41 
42 namespace controller {
43 
44 JointVelocityController::JointVelocityController()
45 : joint_state_(NULL), command_(0), robot_(NULL), last_time_(0), loop_count_(0)
46 {
47 }
48 
50 {
52 }
53 
54 bool JointVelocityController::init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name,
55  const control_toolbox::Pid &pid)
56 {
57  assert(robot);
58  robot_ = robot;
59  last_time_ = robot->getTime();
60 
61  joint_state_ = robot_->getJointState(joint_name);
62  if (!joint_state_)
63  {
64  ROS_ERROR("JointVelocityController could not find joint named \"%s\"\n",
65  joint_name.c_str());
66  return false;
67  }
68 
69  pid_controller_ = pid;
70 
71  return true;
72 }
73 
75 {
76  assert(robot);
77  node_ = n;
78  robot_ = robot;
79 
80  std::string joint_name;
81  if (!node_.getParam("joint", joint_name)) {
82  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
83  return false;
84  }
85  if (!(joint_state_ = robot->getJointState(joint_name)))
86  {
87  ROS_ERROR("Could not find joint \"%s\" (namespace: %s)",
88  joint_name.c_str(), node_.getNamespace().c_str());
89  return false;
90  }
91 
93  return false;
94 
97  (node_, "state", 1));
98 
99  sub_command_ = node_.subscribe<std_msgs::Float64>("command", 1, &JointVelocityController::setCommandCB, this);
100 
101  return true;
102 }
103 
104 
105 void JointVelocityController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
106 {
107  pid_controller_.setGains(p,i,d,i_max,i_min);
108 
109 }
110 
111 void JointVelocityController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
112 {
113  pid_controller_.getGains(p,i,d,i_max,i_min);
114 }
115 
117 {
118  return joint_state_->joint_->name;
119 }
120 
121 // Set the joint velocity command
123 {
124  command_ = cmd;
125 }
126 
127 // Return the current velocity command
129 {
130  cmd = command_;
131 }
132 
134 {
135  assert(robot_ != NULL);
136  ros::Time time = robot_->getTime();
137 
138  double error = command_ - joint_state_->velocity_;
139  dt_ = time - last_time_;
140  double command = pid_controller_.computeCommand(error, dt_);
141  joint_state_->commanded_effort_ += command;
142 
143  if(loop_count_ % 10 == 0)
144  {
146  {
147  controller_state_publisher_->msg_.header.stamp = time;
148  controller_state_publisher_->msg_.set_point = command_;
149  controller_state_publisher_->msg_.process_value = joint_state_->velocity_;
150  controller_state_publisher_->msg_.error = error;
151  controller_state_publisher_->msg_.time_step = dt_.toSec();
152  controller_state_publisher_->msg_.command = command;
153 
154  double dummy;
158  controller_state_publisher_->msg_.i_clamp,
159  dummy);
160  controller_state_publisher_->unlockAndPublish();
161  }
162  }
163  loop_count_++;
164 
165  last_time_ = time;
166 }
167 
168 void JointVelocityController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
169 {
170  command_ = msg->data;
171 }
172 
173 } // namespace
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
pr2_mechanism_model::JointState * joint_state_
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::RobotState * robot_
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool init(const ros::NodeHandle &n, const bool quiet=false)
ROSLIB_DECL std::string command(const std::string &cmd)
void setCommand(double cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
double computeCommand(double error, ros::Duration dt)
def error(args, kwargs)
const std::string & getNamespace() const
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
JointState * getJointState(const std::string &name)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Wed Jun 5 2019 19:34:03