gazebo_ros_katana_gripper.cpp
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2011 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * gazebo_ros_katana_gripper.cpp
20  *
21  * Created on: 29.08.2011
22  * Author: Martin Günther <mguenthe@uos.de>
23  */
24 
26 #include <sensor_msgs/JointState.h>
27 
28 #include <ros/time.h>
29 
30 using namespace gazebo;
31 
33  publish_counter_(0)
34 {
35  this->spinner_thread_ = new boost::thread(boost::bind(&GazeboRosKatanaGripper::spin, this));
36 
37  for (size_t i = 0; i < NUM_JOINTS; ++i)
38  {
39  joints_[i].reset();
40  }
41 
42 }
43 
45 {
46  // delete all gripper actions
47  for (std::size_t i = 0; i != gripper_action_list_.size(); i++)
48  {
49  /* delete object at pointer */
50  delete gripper_action_list_[i];
51  }
52 
53  rosnode_->shutdown();
54  this->spinner_thread_->join();
55  delete this->spinner_thread_;
56  delete rosnode_;
57 }
58 
59 void GazeboRosKatanaGripper::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
60 {
61  this->my_world_ = _parent->GetWorld();
62 
63  this->my_parent_ = _parent;
64  if (!this->my_parent_)
65  {
66  ROS_FATAL("Gazebo_ROS_Create controller requires a Model as its parent");
67  return;
68  }
69 
70  this->node_namespace_ = "katana/";
71  if (_sdf->HasElement("robotNamespace"))
72  this->node_namespace_ = _sdf->Get<std::string>("node_namespace") + "/";
73 
74  torque_ = 0.5;
75  if (_sdf->HasElement("max_torque"))
76  torque_ = _sdf->Get<float>("max_torque");
77 
78  joint_names_.resize(NUM_JOINTS);
79  joint_names_[0] = "katana_r_finger_joint";
80  if (_sdf->HasElement("r_finger_joint"))
81  joint_names_[0] = _sdf->Get<std::string>("r_finger_joint");
82 
83  joint_names_[1] = "katana_r_finger_joint";
84  if (_sdf->HasElement("l_finger_joint"))
85  joint_names_[1] = _sdf->Get<std::string>("l_finger_joint");
86 
87  if (!ros::isInitialized())
88  {
89  int argc = 0;
90  char** argv = NULL;
91  ros::init(argc, argv, "gazebo_ros_katana_gripper",
93  }
94 
96 
97  controller_state_pub_ = rosnode_->advertise<katana_msgs::GripperControllerState>("gripper_controller_state", 1);
98 
99  for (size_t i = 0; i < NUM_JOINTS; ++i)
100  {
101  joints_[i] = my_parent_->GetJoint(joint_names_[i]);
102  if (!joints_[i])
103  gzthrow("The controller couldn't get joint " << joint_names_[i]);
104  }
105 
106  // construct pid controller
107  if (!pid_controller_.init(ros::NodeHandle(*rosnode_, "gripper_pid")))
108  {
109  ROS_FATAL("gazebo_ros_katana_gripper could not construct PID controller!");
110  }
111 
112  // create gripper actions
113  katana_gazebo_plugins::IGazeboRosKatanaGripperAction* gripper_grasp_controller_ =
117 
118  // "register" gripper actions
119  gripper_action_list_.push_back(gripper_grasp_controller_);
120  gripper_action_list_.push_back(gripper_jt_controller_);
121 
122  // set default action
123  active_gripper_action_ = gripper_grasp_controller_;
124  updateGains();
125 
126  // Get the name of the parent model
127  std::string modelName = _sdf->GetParent()->Get<std::string>("name");
128 
129  // Listen to the update event. This event is broadcast every
130  // simulation iteration.
131  this->updateConnection = event::Events::ConnectWorldUpdateBegin(
132  boost::bind(&GazeboRosKatanaGripper::UpdateChild, this));
133  gzdbg << "plugin model name: " << modelName << "\n";
134 
135  ROS_INFO("gazebo_ros_katana_gripper plugin initialized");
136 }
137 
139 {
141  prev_update_time_ = this->my_world_->GetSimTime();
142 }
143 
145 {
146  rosnode_->shutdown();
147 }
148 
150 {
151  // --------------- command joints ---------------
152  common::Time time_now = this->my_world_->GetSimTime();
153  common::Time step_time = time_now - prev_update_time_;
154  prev_update_time_ = time_now;
155  ros::Duration dt = ros::Duration(step_time.Double());
156 
157  double desired_pos[NUM_JOINTS];
158  double actual_pos[NUM_JOINTS];
159  double commanded_effort[NUM_JOINTS];
160 
161  // check for new goals, this my change the active_gripper_action_
163 
164  for (size_t i = 0; i < NUM_JOINTS; ++i)
165  {
166  // desired_pos = 0.3 * sin(0.25 * this->my_world_->GetSimTime());
167  //if ((prev_update_time_.sec / 6) % 2 == 0)
168  // desired_pos[i] = 0.3;
169  //else
170  // desired_pos[i] = -0.44;
171 
173  actual_pos[i] = joints_[i]->GetAngle(0).Radian();
174 
175  commanded_effort[i] = pid_controller_.computeCommand(desired_pos[i] - actual_pos[i], -joints_[i]->GetVelocity(0), dt);
176 
177  if (commanded_effort[i] > torque_)
178  commanded_effort[i] = torque_;
179  else if (commanded_effort[i] < -torque_)
180  commanded_effort[i] = -torque_;
181 
182  joints_[i]->SetForce(0, commanded_effort[i]);
183 
184  // TODO: ensure that both joints are always having (approximately)
185  // the same joint position, even if one is blocked by an object
186  }
187  if (fabs(commanded_effort[0]) > 0.001)
188  ROS_DEBUG("efforts: r %f, l %f (max: %f)", commanded_effort[0], commanded_effort[1], torque_);
189 
190  // --------------- update gripper_grasp_controller ---------------
191  for (size_t i = 0; i < NUM_JOINTS; ++i)
192  {
193 
194  // update all actions
195  for (std::size_t i = 0; i != gripper_action_list_.size(); i++)
196  {
197  gripper_action_list_[i]->setCurrentPoint(joints_[i]->GetAngle(0).Radian(), joints_[i]->GetVelocity(0));
198  }
199 
200  }
201 
202  // --------------- limit publishing frequency to 25 Hz ---------------
203  publish_counter_ = ((publish_counter_ + 1) % 40);
204 
205  if (publish_counter_ == 0)
206  {
207  // --------------- publish gripper controller state ---------------
208  katana_msgs::GripperControllerState controller_state;
209  controller_state.header.stamp = ros::Time::now();
210  for (size_t i = 0; i < NUM_JOINTS; ++i)
211  {
212  controller_state.name.push_back(joints_[i]->GetName());
213  controller_state.actual.push_back(actual_pos[i]);
214  controller_state.desired.push_back(desired_pos[i]);
215  controller_state.error.push_back(desired_pos[i] - actual_pos[i]);
216  }
217 
218  controller_state_pub_.publish(controller_state);
219 
220  // don't publish joint states: The pr2_controller_manager publishes joint states for
221  // ALL joints, not just the ones it controls.
222  //
223  // // --------------- publish joint states ---------------
224  // js_.header.stamp = ros::Time::now();
225  //
226  // for (size_t i = 0; i < NUM_JOINTS; ++i)
227  // {
228  // js_.position[i] = joints_[i]->GetAngle(0).Radian();
229  // js_.velocity[i] = joints_[i]->GetVelocity(0);
230  // js_.effort[i] = commanded_effort[i];
231  //
232  // ROS_DEBUG("publishing gripper joint state %d (effort: %f)", i, commanded_effort[i]);
233  // }
234  //
235  // joint_state_pub_.publish(js_);
236  }
237 }
238 
243 {
244  //TODO: improve the selection of the action, maybe prefer newer started actions (but how to know?)
245  // atm the list gives some kind of priority, and it its impossible to cancel a goal
246  // by submitting a new one to another action (but you can cancel the goal via a message)
247 
248  // search for a new action if the current (or default on) is finished with its goal
249  // if we cant find a new action, just use the current one
251  {
252 
253  // find a new action with a goal
254  for (std::size_t i = 0; i != gripper_action_list_.size(); i++)
255  {
256  // just use the first found
257  if (gripper_action_list_[i]->hasActiveGoal())
258  {
259  // change the active gripper action
261  updateGains();
262 
263  break;
264  }
265  }
266  }
267 }
268 
270 {
271  // PID Controller parameters (gains)
272  double p, i, d, i_max, i_min;
273  // get current values
274  pid_controller_.getGains(p, i, d, i_max, i_min);
275  // overwrite with defaults from the active action
276  active_gripper_action_->getGains(p, i, d, i_max, i_min);
277  // set changed values
278  pid_controller_.setGains(p, i, d, i_max, i_min);
279 }
280 
282 {
283  while (ros::ok())
284  ros::spinOnce();
285 }
286 
d
#define ROS_FATAL(...)
void publish(const boost::shared_ptr< M > &message) const
katana_gazebo_plugins::IGazeboRosKatanaGripperAction * active_gripper_action_
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)
ROSCPP_DECL bool isInitialized()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
GZ_REGISTER_MODEL_PLUGIN(GazeboRosKatanaGripper)
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)=0
bool init(const ros::NodeHandle &n, const bool quiet=false)
std::vector< std::string > joint_names_
double computeCommand(double error, ros::Duration dt)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual GRKAPoint getNextDesiredPoint(ros::Time time)=0
std::vector< katana_gazebo_plugins::IGazeboRosKatanaGripperAction * > gripper_action_list_
static Time now()
physics::JointPtr joints_[NUM_JOINTS]
ROSCPP_DECL void spinOnce()
float torque_
Torque applied to the joints.
#define ROS_DEBUG(...)


katana_gazebo_plugins
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:34