gazebo_ros_katana_gripper.cpp
Go to the documentation of this file.
00001 /*
00002  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
00003  * Copyright (C) 2011  University of Osnabrück
00004  *
00005  * This program is free software; you can redistribute it and/or
00006  * modify it under the terms of the GNU General Public License
00007  * as published by the Free Software Foundation; either version 2
00008  * of the License, or (at your option) any later version.
00009  *
00010  * This program is distributed in the hope that it will be useful,
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013  * GNU General Public License for more details.
00014  *
00015  * You should have received a copy of the GNU General Public License
00016  * along with this program; if not, write to the Free Software
00017  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.
00018  *
00019  * gazebo_ros_katana_gripper.cpp
00020  *
00021  *  Created on: 29.08.2011
00022  *      Author: Martin Günther <mguenthe@uos.de>
00023  */
00024 
00025 #include <katana_gazebo_plugins/gazebo_ros_katana_gripper.h>
00026 #include <sensor_msgs/JointState.h>
00027 
00028 #include <ros/time.h>
00029 
00030 using namespace gazebo;
00031 
00032 GazeboRosKatanaGripper::GazeboRosKatanaGripper() :
00033     publish_counter_(0)
00034 {
00035   this->spinner_thread_ = new boost::thread(boost::bind(&GazeboRosKatanaGripper::spin, this));
00036 
00037   for (size_t i = 0; i < NUM_JOINTS; ++i)
00038   {
00039     joints_[i].reset();
00040   }
00041 
00042 }
00043 
00044 GazeboRosKatanaGripper::~GazeboRosKatanaGripper()
00045 {
00046   // delete all gripper actions
00047   for (std::size_t i = 0; i != gripper_action_list_.size(); i++)
00048   {
00049     /* delete object at pointer */
00050     delete gripper_action_list_[i];
00051   }
00052 
00053   rosnode_->shutdown();
00054   this->spinner_thread_->join();
00055   delete this->spinner_thread_;
00056   delete rosnode_;
00057 }
00058 
00059 void GazeboRosKatanaGripper::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00060 {
00061   this->my_world_ = _parent->GetWorld();
00062 
00063   this->my_parent_ = _parent;
00064   if (!this->my_parent_)
00065   {
00066     ROS_FATAL("Gazebo_ROS_Create controller requires a Model as its parent");
00067     return;
00068   }
00069 
00070   this->node_namespace_ = "katana/";
00071   if (_sdf->HasElement("robotNamespace"))
00072     this->node_namespace_ = _sdf->GetElement("node_namespace")->GetValueString() + "/";
00073 
00074   torque_ = 0.5;
00075   if (_sdf->HasElement("max_torque"))
00076     torque_ = _sdf->GetElement("max_torque")->GetValueDouble();
00077 
00078   joint_names_.resize(NUM_JOINTS);
00079   joint_names_[0] = "katana_r_finger_joint";
00080   if (_sdf->HasElement("r_finger_joint"))
00081     joint_names_[0] = _sdf->GetElement("r_finger_joint")->GetValueString();
00082 
00083   joint_names_[1] = "katana_r_finger_joint";
00084   if (_sdf->HasElement("l_finger_joint"))
00085     joint_names_[1] = _sdf->GetElement("l_finger_joint")->GetValueString();
00086 
00087   if (!ros::isInitialized())
00088   {
00089     int argc = 0;
00090     char** argv = NULL;
00091     ros::init(argc, argv, "gazebo_ros_katana_gripper",
00092               ros::init_options::NoSigintHandler | ros::init_options::AnonymousName);
00093   }
00094 
00095   rosnode_ = new ros::NodeHandle(node_namespace_);
00096 
00097   controller_state_pub_ = rosnode_->advertise<katana_msgs::GripperControllerState>("gripper_controller_state", 1);
00098 
00099   for (size_t i = 0; i < NUM_JOINTS; ++i)
00100   {
00101     joints_[i] = my_parent_->GetJoint(joint_names_[i]);
00102     if (!joints_[i])
00103       gzthrow("The controller couldn't get joint " << joint_names_[i]);
00104   }
00105 
00106   // construct pid controller
00107   if (!pid_controller_.init(ros::NodeHandle(*rosnode_, "gripper_pid")))
00108   {
00109     ROS_FATAL("gazebo_ros_katana_gripper could not construct PID controller!");
00110   }
00111 
00112   // create gripper actions
00113   katana_gazebo_plugins::IGazeboRosKatanaGripperAction* gripper_grasp_controller_ =
00114       new katana_gazebo_plugins::KatanaGripperGraspController(ros::NodeHandle(node_namespace_));
00115   katana_gazebo_plugins::IGazeboRosKatanaGripperAction* gripper_jt_controller_ =
00116       new katana_gazebo_plugins::KatanaGripperJointTrajectoryController(ros::NodeHandle(node_namespace_));
00117 
00118   // "register" gripper actions
00119   gripper_action_list_.push_back(gripper_grasp_controller_);
00120   gripper_action_list_.push_back(gripper_jt_controller_);
00121 
00122   // set default action
00123   active_gripper_action_ = gripper_grasp_controller_;
00124 
00125   // Get the name of the parent model
00126   std::string modelName = _sdf->GetParent()->GetValueString("name");
00127 
00128   // Listen to the update event. This event is broadcast every
00129   // simulation iteration.
00130   this->updateConnection = event::Events::ConnectWorldUpdateStart(
00131       boost::bind(&GazeboRosKatanaGripper::UpdateChild, this));
00132   gzdbg << "plugin model name: " << modelName << "\n";
00133 
00134   ROS_INFO("gazebo_ros_katana_gripper plugin initialized");
00135 }
00136 
00137 void GazeboRosKatanaGripper::InitChild()
00138 {
00139   pid_controller_.reset();
00140   prev_update_time_ = this->my_world_->GetSimTime();
00141 }
00142 
00143 void GazeboRosKatanaGripper::FiniChild()
00144 {
00145   rosnode_->shutdown();
00146 }
00147 
00148 void GazeboRosKatanaGripper::UpdateChild()
00149 {
00150   // --------------- command joints  ---------------
00151   common::Time time_now = this->my_world_->GetSimTime();
00152   common::Time step_time = time_now - prev_update_time_;
00153   prev_update_time_ = time_now;
00154   ros::Duration dt = ros::Duration(step_time.Double());
00155 
00156   double desired_pos[NUM_JOINTS];
00157   double actual_pos[NUM_JOINTS];
00158   double commanded_effort[NUM_JOINTS];
00159 
00160   // check for new goals, this my change the active_gripper_action_
00161   this->updateActiveGripperAction();
00162 
00163   // PID Controller paramters (gains)
00164 
00165   double p, i, d, i_max, i_min;
00166   // get current values
00167   pid_controller_.getGains(p, i, d, i_max, i_min);
00168   // change values by the active action
00169   active_gripper_action_->getGains(p, i, d, i_max, i_min);
00170   // set changed values
00171   pid_controller_.setGains(p, i, d, i_max, i_min);
00172 
00173   for (size_t i = 0; i < NUM_JOINTS; ++i)
00174   {
00175     // desired_pos = 0.3 * sin(0.25 * this->my_world_->GetSimTime());
00176     //if ((prev_update_time_.sec / 6) % 2 == 0)
00177     //  desired_pos[i] = 0.3;
00178     //else
00179     //  desired_pos[i] = -0.44;
00180 
00181     desired_pos[i] = active_gripper_action_->getNextDesiredPoint(ros::Time::now()).position;
00182     actual_pos[i] = joints_[i]->GetAngle(0).Radian();
00183 
00184     commanded_effort[i] = pid_controller_.updatePid(actual_pos[i] - desired_pos[i], joints_[i]->GetVelocity(0), dt);
00185 
00186     if (commanded_effort[i] > torque_)
00187       commanded_effort[i] = torque_;
00188     else if (commanded_effort[i] < -torque_)
00189       commanded_effort[i] = -torque_;
00190 
00191     joints_[i]->SetForce(0, commanded_effort[i]);
00192 
00193     // TODO: ensure that both joints are always having (approximately)
00194     // the same joint position, even if one is blocked by an object
00195   }
00196   if (fabs(commanded_effort[0]) > 0.001)
00197     ROS_DEBUG("efforts: r %f, l %f (max: %f)", commanded_effort[0], commanded_effort[1], torque_);
00198 
00199   // --------------- update gripper_grasp_controller  ---------------
00200   for (size_t i = 0; i < NUM_JOINTS; ++i)
00201   {
00202 
00203     // update all actions
00204     for (std::size_t i = 0; i != gripper_action_list_.size(); i++)
00205     {
00206       gripper_action_list_[i]->setCurrentPoint(joints_[i]->GetAngle(0).Radian(), joints_[i]->GetVelocity(0));
00207     }
00208 
00209   }
00210 
00211   // --------------- limit publishing frequency to 25 Hz ---------------
00212   publish_counter_ = ((publish_counter_ + 1) % 40);
00213 
00214   if (publish_counter_ == 0)
00215   {
00216     // --------------- publish gripper controller state  ---------------
00217     katana_msgs::GripperControllerState controller_state;
00218     controller_state.header.stamp = ros::Time::now();
00219     for (size_t i = 0; i < NUM_JOINTS; ++i)
00220     {
00221       controller_state.name.push_back(joints_[i]->GetName());
00222       controller_state.actual.push_back(actual_pos[i]);
00223       controller_state.desired.push_back(desired_pos[i]);
00224       controller_state.error.push_back(desired_pos[i] - actual_pos[i]);
00225     }
00226 
00227     controller_state_pub_.publish(controller_state);
00228 
00229     // don't publish joint states: The pr2_controller_manager publishes joint states for
00230     // ALL joints, not just the ones it controls.
00231     //
00232     //    // --------------- publish joint states ---------------
00233     //    js_.header.stamp = ros::Time::now();
00234     //
00235     //    for (size_t i = 0; i < NUM_JOINTS; ++i)
00236     //    {
00237     //      js_.position[i] = joints_[i]->GetAngle(0).adian();
00238     //      js_.velocity[i] = joints_[i]->GetVelocity(0);
00239     //      js_.effort[i] = commanded_effort[i];
00240     //
00241     //      ROS_DEBUG("publishing gripper joint state %d (effort: %f)", i, commanded_effort[i]);
00242     //    }
00243     //
00244     //    joint_state_pub_.publish(js_);
00245   }
00246 }
00247 
00251 void GazeboRosKatanaGripper::updateActiveGripperAction()
00252 {
00253   //TODO: improve the selection of the action, maybe prefer newer started actions (but how to know?)
00254   //      atm the list gives some kind of priority, and it its impossible to cancel a goal
00255   //      by submitting a new one to another action (but you can cancel the goal via a message)
00256 
00257   // search for a new action if the current (or default on) is finished with its goal
00258   // if we cant find a new action, just use the current one
00259   if (!active_gripper_action_->hasActiveGoal())
00260   {
00261 
00262     // find a new action with a goal
00263     for (std::size_t i = 0; i != gripper_action_list_.size(); i++)
00264     {
00265       // just use the first found
00266       if (gripper_action_list_[i]->hasActiveGoal())
00267       {
00268         // change the active gripper action
00269         active_gripper_action_ = gripper_action_list_[i];
00270         break;
00271       }
00272     }
00273 
00274   }
00275 
00276 }
00277 
00278 void GazeboRosKatanaGripper::spin()
00279 {
00280   while (ros::ok())
00281     ros::spinOnce();
00282 }
00283 
00284 GZ_REGISTER_MODEL_PLUGIN(GazeboRosKatanaGripper);


katana_gazebo_plugins
Author(s): Martin Günther
autogenerated on Mon Oct 6 2014 10:47:21