joint_position_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 
36 #include "angles/angles.h"
38 
40 
41 using namespace std;
42 
43 namespace controller {
44 
45 JointPositionController::JointPositionController()
46 : joint_state_(NULL), command_(0),
47  loop_count_(0), initialized_(false), robot_(NULL), last_time_(0)
48 {
49 }
50 
52 {
54 }
55 
56 bool JointPositionController::init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name,
57  const control_toolbox::Pid &pid)
58 {
59  assert(robot);
60  robot_ = robot;
61  last_time_ = robot->getTime();
62 
63  joint_state_ = robot_->getJointState(joint_name);
64  if (!joint_state_)
65  {
66  ROS_ERROR("JointPositionController could not find joint named \"%s\"\n",
67  joint_name.c_str());
68  return false;
69  }
71  {
72  ROS_ERROR("Joint %s not calibrated for JointPositionController", joint_name.c_str());
73  return false;
74  }
75 
76  pid_controller_ = pid;
77 
78  return true;
79 }
80 
82 {
83  assert(robot);
84  node_ = n;
85 
86  std::string joint_name;
87  if (!node_.getParam("joint", joint_name)) {
88  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
89  return false;
90  }
91 
93  if (!pid.init(ros::NodeHandle(node_, "pid")))
94  return false;
95 
98  (node_, "state", 1));
99 
100  sub_command_ = node_.subscribe<std_msgs::Float64>("command", 1, &JointPositionController::setCommandCB, this);
101 
102  return init(robot, joint_name, pid);
103 }
104 
105 
106 void JointPositionController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
107 {
108  pid_controller_.setGains(p,i,d,i_max,i_min);
109 }
110 
111 void JointPositionController::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 position command
123 {
124  command_ = cmd;
125 }
126 
127 // Return the current position command
129 {
130  cmd = command_;
131 }
132 
134 {
136  return;
137 
138  assert(robot_ != NULL);
139  double error(0);
140  ros::Time time = robot_->getTime();
141  assert(joint_state_->joint_);
142  dt_= time - last_time_;
143 
144  if (!initialized_)
145  {
146  initialized_ = true;
148  }
149 
150  if(joint_state_->joint_->type == urdf::Joint::REVOLUTE)
151  {
154  command_,
155  joint_state_->joint_->limits->lower,
156  joint_state_->joint_->limits->upper,
157  error);
158 
159  }
160  else if(joint_state_->joint_->type == urdf::Joint::CONTINUOUS)
161  {
163  command_);
164  }
165  else //prismatic
166  {
167  error = command_ - joint_state_->position_;
168  }
169 
170  double commanded_effort = pid_controller_.computeCommand(error,
171  0.0 - joint_state_->velocity_, dt_); // assuming desired velocity is 0
172  joint_state_->commanded_effort_ = commanded_effort;
173 
174  if(loop_count_ % 10 == 0)
175  {
177  {
178  controller_state_publisher_->msg_.header.stamp = time;
179  controller_state_publisher_->msg_.set_point = command_;
180  controller_state_publisher_->msg_.process_value = joint_state_->position_;
181  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
182  controller_state_publisher_->msg_.error = error;
183  controller_state_publisher_->msg_.time_step = dt_.toSec();
184  controller_state_publisher_->msg_.command = commanded_effort;
185 
186  double dummy;
190  controller_state_publisher_->msg_.i_clamp,
191  dummy);
192  controller_state_publisher_->unlockAndPublish();
193  }
194  }
195  loop_count_++;
196 
197  last_time_ = time;
198 }
199 
200 void JointPositionController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
201 {
202  command_ = msg->data;
203 }
204 
205 }
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void setCommand(double cmd)
Give set position of the joint for next update: 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 setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
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::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
pr2_mechanism_model::RobotState * robot_
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::JointState * joint_state_
bool init(const ros::NodeHandle &n, const bool quiet=false)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
double computeCommand(double error, ros::Duration dt)
def error(args, kwargs)
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool getParam(const std::string &key, std::string &s) const
virtual void update()
Issues commands to the joint. Should be called at regular intervals.
#define ROS_ERROR(...)
def shortest_angular_distance(from_angle, to_angle)


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Mon Jun 10 2019 14:26:26