aubo_hardware_interface.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************
00034 
00035  Author: Dave Coleman
00036  */
00037 
00038 #include <aubo_new_driver/aubo_hardware_interface.h>
00039 
00040 namespace ros_control_aubo {
00041 
00042 AuboHardwareInterface::AuboHardwareInterface(ros::NodeHandle& nh, AuboNewDriver* robot) :
00043                 nh_(nh), robot_(robot) {
00044         // Initialize shared memory and interfaces here
00045         init(); // this implementation loads from rosparam
00046 
00047         max_vel_change_ = 0.12; // equivalent of an acceleration of 15 rad/sec^2
00048 
00049         ROS_INFO_NAMED("aubo_hardware_interface", "Loaded aubo_hardware_interface.");
00050 }
00051 
00052 void AuboHardwareInterface::init() {
00053         ROS_INFO_STREAM_NAMED("aubo_hardware_interface",
00054                         "Reading rosparams from namespace: " << nh_.getNamespace());
00055 
00056         // Get joint names
00057         nh_.getParam("hardware_interface/joints", joint_names_);
00058         if (joint_names_.size() == 0) {
00059                 ROS_FATAL_STREAM_NAMED("aubo_hardware_interface",
00060                                 "No joints found on parameter server for controller, did you load the proper yaml file?" << " Namespace: " << nh_.getNamespace());
00061                 exit(-1);
00062         }
00063         num_joints_ = joint_names_.size();
00064 
00065         // Resize vectors
00066         joint_position_.resize(num_joints_);
00067         joint_velocity_.resize(num_joints_);
00068         joint_effort_.resize(num_joints_);
00069         joint_position_command_.resize(num_joints_);
00070         joint_velocity_command_.resize(num_joints_);
00071         prev_joint_velocity_command_.resize(num_joints_);
00072 
00073         // Initialize controller
00074         for (std::size_t i = 0; i < num_joints_; ++i) {
00075                 ROS_DEBUG_STREAM_NAMED("aubo_hardware_interface",
00076                                 "Loading joint name: " << joint_names_[i]);
00077 
00078                 // Create joint state interface
00079                 joint_state_interface_.registerHandle(
00080                                 hardware_interface::JointStateHandle(joint_names_[i],
00081                                                 &joint_position_[i], &joint_velocity_[i],
00082                                                 &joint_effort_[i]));
00083 
00084                 // Create position joint interface
00085                 position_joint_interface_.registerHandle(
00086                                 hardware_interface::JointHandle(
00087                                                 joint_state_interface_.getHandle(joint_names_[i]),
00088                                                 &joint_position_command_[i]));
00089 
00090                 // Create velocity joint interface
00091                 velocity_joint_interface_.registerHandle(
00092                                 hardware_interface::JointHandle(
00093                                                 joint_state_interface_.getHandle(joint_names_[i]),
00094                                                 &joint_velocity_command_[i]));
00095                 prev_joint_velocity_command_[i] = 0.;
00096         }
00097 
00098         // Create force torque interface
00099         force_torque_interface_.registerHandle(
00100                         hardware_interface::ForceTorqueSensorHandle("wrench", "",
00101                                         robot_force_, robot_torque_));
00102 
00103         registerInterface(&joint_state_interface_); // From RobotHW base class.
00104         registerInterface(&position_joint_interface_); // From RobotHW base class.
00105         registerInterface(&velocity_joint_interface_); // From RobotHW base class.
00106         registerInterface(&force_torque_interface_); // From RobotHW base class.
00107         velocity_interface_running_ = false;
00108         position_interface_running_ = false;
00109 }
00110 
00111 void AuboHardwareInterface::read() {
00112         std::vector<double> pos, vel, current, tcp;
00113     pos = robot_->rt_interface_->robot_state_->getJonitPosition();
00114     vel = robot_->rt_interface_->robot_state_->getJonitVelocity();
00115     current = robot_->rt_interface_->robot_state_->getJointCurrent();
00116     tcp = robot_->rt_interface_->robot_state_->getTcpForce();
00117         for (std::size_t i = 0; i < num_joints_; ++i) {
00118                 joint_position_[i] = pos[i];
00119                 joint_velocity_[i] = vel[i];
00120                 joint_effort_[i] = current[i];
00121         }
00122         for (std::size_t i = 0; i < 3; ++i) {
00123                 robot_force_[i] = tcp[i];
00124                 robot_torque_[i] = tcp[i + 3];
00125         }
00126 }
00127 
00128 void AuboHardwareInterface::setMaxVelChange(double inp) {
00129         max_vel_change_ = inp;
00130 }
00131 
00132 void AuboHardwareInterface::write() {
00133         if (velocity_interface_running_) {
00134                 std::vector<double> cmd;
00135                 //do some rate limiting
00136                 cmd.resize(joint_velocity_command_.size());
00137                 for (unsigned int i = 0; i < joint_velocity_command_.size(); i++) {
00138                         cmd[i] = joint_velocity_command_[i];
00139                         if (cmd[i] > prev_joint_velocity_command_[i] + max_vel_change_) {
00140                                 cmd[i] = prev_joint_velocity_command_[i] + max_vel_change_;
00141                         } else if (cmd[i]
00142                                         < prev_joint_velocity_command_[i] - max_vel_change_) {
00143                                 cmd[i] = prev_joint_velocity_command_[i] - max_vel_change_;
00144                         }
00145                         prev_joint_velocity_command_[i] = cmd[i];
00146                 }
00147         robot_->setSpeed(cmd[0], cmd[1], cmd[2], cmd[3], cmd[4], cmd[5],  max_vel_change_*125);
00148     }
00149     else if (position_interface_running_) {
00150         robot_->servoj(joint_position_command_);
00151         }
00152 }
00153 
00154 bool AuboHardwareInterface::canSwitch(
00155                 const std::list<hardware_interface::ControllerInfo> &start_list,
00156                 const std::list<hardware_interface::ControllerInfo> &stop_list) const {
00157         for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
00158                         start_list.begin(); controller_it != start_list.end();
00159                         ++controller_it) {
00160                 if (controller_it->hardware_interface
00161                                 == "hardware_interface::VelocityJointInterface") {
00162                         if (velocity_interface_running_) {
00163                                 ROS_ERROR(
00164                                                 "%s: An interface of that type (%s) is already running",
00165                                                 controller_it->name.c_str(),
00166                                                 controller_it->hardware_interface.c_str());
00167                                 return false;
00168                         }
00169                         if (position_interface_running_) {
00170                                 bool error = true;
00171                                 for (std::list<hardware_interface::ControllerInfo>::const_iterator stop_controller_it =
00172                                                 stop_list.begin();
00173                                                 stop_controller_it != stop_list.end();
00174                                                 ++stop_controller_it) {
00175                                         if (stop_controller_it->hardware_interface
00176                                                         == "hardware_interface::PositionJointInterface") {
00177                                                 error = false;
00178                                                 break;
00179                                         }
00180                                 }
00181                                 if (error) {
00182                                         ROS_ERROR(
00183                                                         "%s (type %s) can not be run simultaneously with a PositionJointInterface",
00184                                                         controller_it->name.c_str(),
00185                                                         controller_it->hardware_interface.c_str());
00186                                         return false;
00187                                 }
00188                         }
00189                 } else if (controller_it->hardware_interface
00190                                 == "hardware_interface::PositionJointInterface") {
00191                         if (position_interface_running_) {
00192                                 ROS_ERROR(
00193                                                 "%s: An interface of that type (%s) is already running",
00194                                                 controller_it->name.c_str(),
00195                                                 controller_it->hardware_interface.c_str());
00196                                 return false;
00197                         }
00198                         if (velocity_interface_running_) {
00199                                 bool error = true;
00200                                 for (std::list<hardware_interface::ControllerInfo>::const_iterator stop_controller_it =
00201                                                 stop_list.begin();
00202                                                 stop_controller_it != stop_list.end();
00203                                                 ++stop_controller_it) {
00204                                         if (stop_controller_it->hardware_interface
00205                                                         == "hardware_interface::VelocityJointInterface") {
00206                                                 error = false;
00207                                                 break;
00208                                         }
00209                                 }
00210                                 if (error) {
00211                                         ROS_ERROR(
00212                                                         "%s (type %s) can not be run simultaneously with a VelocityJointInterface",
00213                                                         controller_it->name.c_str(),
00214                                                         controller_it->hardware_interface.c_str());
00215                                         return false;
00216                                 }
00217                         }
00218                 }
00219         }
00220 
00221 // we can always stop a controller
00222         return true;
00223 }
00224 
00225 void AuboHardwareInterface::doSwitch(
00226                 const std::list<hardware_interface::ControllerInfo>& start_list,
00227                 const std::list<hardware_interface::ControllerInfo>& stop_list) {
00228         for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
00229                         stop_list.begin(); controller_it != stop_list.end();
00230                         ++controller_it) {
00231                 if (controller_it->hardware_interface
00232                                 == "hardware_interface::VelocityJointInterface") {
00233                         velocity_interface_running_ = false;
00234                         ROS_DEBUG("Stopping velocity interface");
00235                 }
00236                 if (controller_it->hardware_interface
00237                                 == "hardware_interface::PositionJointInterface") {
00238                         position_interface_running_ = false;
00239                         std::vector<double> tmp;
00240             robot_->closeServo(tmp);
00241                         ROS_DEBUG("Stopping position interface");
00242                 }
00243         }
00244         for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
00245                         start_list.begin(); controller_it != start_list.end();
00246                         ++controller_it) {
00247         if (controller_it->hardware_interface
00248                                 == "hardware_interface::VelocityJointInterface") {
00249                         velocity_interface_running_ = true;
00250                         ROS_DEBUG("Starting velocity interface");
00251         }
00252                 if (controller_it->hardware_interface
00253                                 == "hardware_interface::PositionJointInterface") {
00254                         position_interface_running_ = true;
00255             robot_->openServo();
00256                         ROS_DEBUG("Starting position interface");
00257                 }
00258         }
00259 
00260 }
00261 
00262 } // namespace
00263 


aubo_new_driver
Author(s): liuxin
autogenerated on Sat Jun 8 2019 19:06:02