pr2_gripper_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 Pr2GripperController::Pr2GripperController()
46 : joint_state_(NULL),
47  loop_count_(0), robot_(NULL), last_time_(0)
48 {
49 }
50 
52 {
54 }
55 
57 {
58  assert(robot);
59  node_ = n;
60  robot_ = robot;
61 
62  std::string joint_name;
63  if (!node_.getParam("joint", joint_name)) {
64  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
65  return false;
66  }
67  if (!(joint_state_ = robot_->getJointState(joint_name)))
68  {
69  ROS_ERROR("Could not find joint named \"%s\" (namespace: %s)",
70  joint_name.c_str(), node_.getNamespace().c_str());
71  return false;
72  }
73  if (joint_state_->joint_->type != urdf::Joint::PRISMATIC)
74  {
75  ROS_ERROR("The joint \"%s\" was not prismatic (namespace: %s)",
76  joint_name.c_str(), node_.getNamespace().c_str());
77  return false;
78  }
79 
81  {
82  ROS_ERROR("Joint %s is not calibrated (namespace: %s)",
83  joint_state_->joint_->name.c_str(), node_.getNamespace().c_str());
84  return false;
85  }
86 
87  if (!pid_.init(ros::NodeHandle(node_, "pid")))
88  return false;
89 
92  (node_, "state", 1));
93 
94  sub_command_ = node_.subscribe<pr2_controllers_msgs::Pr2GripperCommand>(
95  "command", 1, &Pr2GripperController::commandCB, this);
96 
97  return true;
98 }
99 
101 {
103  return;
104 
105  assert(robot_ != NULL);
106  double error(0);
107  ros::Time time = robot_->getTime();
108  assert(joint_state_->joint_);
109  ros::Duration dt = time - last_time_;
110 
111  pr2_controllers_msgs::Pr2GripperCommandConstPtr command;
112  command_box_.get(command);
113  assert(command);
114 
115  // Computes the position error
116  error = command->position - joint_state_->position_;
117 
118  // Sets the effort (limited)
119  double effort = pid_.computeCommand(error, 0.0 - joint_state_->velocity_, dt);
120  if (command->max_effort >= 0.0)
121  {
122  effort = std::max(-command->max_effort, std::min(effort, command->max_effort));
123  }
125 
126  if(loop_count_ % 10 == 0)
127  {
129  {
130  controller_state_publisher_->msg_.header.stamp = time;
131  controller_state_publisher_->msg_.set_point = command->position;
132  controller_state_publisher_->msg_.process_value = joint_state_->position_;
133  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
134  controller_state_publisher_->msg_.error = error;
135  controller_state_publisher_->msg_.time_step = dt.toSec();
136  controller_state_publisher_->msg_.command = effort;
137 
138  double dummy;
142  controller_state_publisher_->msg_.i_clamp,
143  dummy);
144  controller_state_publisher_->unlockAndPublish();
145  }
146  }
147  loop_count_++;
148 
149  last_time_ = time;
150 }
151 
152 void Pr2GripperController::commandCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr& msg)
153 {
154  command_box_.set(msg);
155 }
156 
157 }
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void commandCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr &msg)
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)
realtime_tools::RealtimeBox< pr2_controllers_msgs::Pr2GripperCommandConstPtr > command_box_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
virtual void update()
Issues commands to the joint. Should be called at regular intervals.
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::RobotState * robot_
bool init(const ros::NodeHandle &n, const bool quiet=false)
ROSLIB_DECL std::string command(const std::string &cmd)
double computeCommand(double error, ros::Duration dt)
def error(args, kwargs)
const std::string & getNamespace() const
void set(const T &value)
JointState * getJointState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
pr2_mechanism_model::JointState * joint_state_
#define ROS_ERROR(...)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Mon Jun 10 2019 14:26:33