ros_ethercat.hpp
Go to the documentation of this file.
00001 /*
00002  * ros_ethercat.hpp
00003  *
00004  *  Created on: 7 Jan 2014
00005  *      Author: Manos Nikolaidis
00006  *
00007  * Software License Agreement (BSD License)
00008  *
00009  *  Copyright (c) 2014, Shadow Robot Company Ltd.
00010  *  All rights reserved.
00011  *
00012  *  Redistribution and use in source and binary forms, with or without
00013  *  modification, are permitted provided that the following conditions
00014  *  are met:
00015  *
00016  *   * Redistributions of source code must retain the above copyright
00017  *     notice, this list of conditions and the following disclaimer.
00018  *   * Redistributions in binary form must reproduce the above
00019  *     copyright notice, this list of conditions and the following
00020  *     disclaimer in the documentation and/or other materials provided
00021  *     with the distribution.
00022  *   * Neither the name of the Willow Garage nor the names of its
00023  *     contributors may be used to endorse or promote products derived
00024  *     from this software without specific prior written permission.
00025  *
00026  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00027  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00028  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00029  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00030  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00031  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00032  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00033  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00034  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00035  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00036  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00037  *  POSSIBILITY OF SUCH DAMAGE.
00038  *********************************************************************/
00039 
00040 #ifndef ROS_ETHERCAT_MODEL_ROS_ETHERCAT_HPP_
00041 #define ROS_ETHERCAT_MODEL_ROS_ETHERCAT_HPP_
00042 
00043 #include <ros/ros.h>
00044 #include <ros/console.h>
00045 #include <hardware_interface/robot_hw.h>
00046 #include <hardware_interface/joint_state_interface.h>
00047 #include <hardware_interface/joint_command_interface.h>
00048 #include <controller_manager/controller_manager.h>
00049 #include <pr2_mechanism_msgs/MechanismStatistics.h>
00050 #include "ros_ethercat_model/robot_state.hpp"
00051 #include "ros_ethercat_model/mech_stats_publisher.hpp"
00052 #include "ros_ethercat_hardware/ethercat_hardware.h"
00053 
00054 
00072 using std::string;
00073 using boost::ptr_unordered_map;
00074 using ros_ethercat_model::JointState;
00075 using ros_ethercat_model::Actuator;
00076 using ros_ethercat_model::Transmission;
00077 
00078 static const string name = "ros_ethercat";
00079 
00080 class RosEthercat : public hardware_interface::RobotHW
00081 {
00082 public:
00083   RosEthercat(ros::NodeHandle &nh, const string &eth, bool allow, TiXmlElement* config) :
00084     cm_node_(nh, "ethercat_controller_manager"),
00085     model_(config),
00086     ec_(name, static_cast<hardware_interface::HardwareInterface*> (&model_), eth, allow)
00087   {
00088     for (ptr_unordered_map<string, JointState>::iterator it = model_.joint_states_.begin();
00089          it != model_.joint_states_.end();
00090          ++it)
00091     {
00092       hardware_interface::JointStateHandle jsh(it->first,
00093                                                &it->second->position_,
00094                                                &it->second->velocity_,
00095                                                &it->second->measured_effort_);
00096       joint_state_interface_.registerHandle(jsh);
00097 
00098       hardware_interface::JointHandle jh(joint_state_interface_.getHandle(it->first),
00099                                          &it->second->commanded_effort_);
00100       joint_command_interface_.registerHandle(jh);
00101       effort_joint_interface_.registerHandle(jh);
00102       position_joint_interface_.registerHandle(jh);
00103     }
00104 
00105     if (!model_.joint_states_.empty())
00106       mech_stats_publisher_.reset(new MechStatsPublisher(nh, model_));
00107 
00108     registerInterface(&model_);
00109     registerInterface(&joint_state_interface_);
00110     registerInterface(&joint_command_interface_);
00111     registerInterface(&effort_joint_interface_);
00112     registerInterface(&position_joint_interface_);
00113   }
00114   virtual ~RosEthercat()
00115   {
00116   }
00117 
00119   void read()
00120   {
00121     ec_.update(false, false);
00122 
00123     model_.current_time_ = ros::Time::now();
00124     model_.propagateActuatorPositionToJointPosition();
00125 
00126     for (ptr_unordered_map<string, JointState>::iterator it = model_.joint_states_.begin();
00127          it != model_.joint_states_.end();
00128          ++it)
00129     {
00130       it->second->joint_statistics_.update(it->second);
00131       it->second->commanded_effort_ = 0;
00132     }
00133   }
00134 
00136   void write()
00137   {
00139     for (ptr_unordered_map<string, JointState>::iterator it = model_.joint_states_.begin();
00140          it != model_.joint_states_.end();
00141          ++it)
00142     {
00143       it->second->enforceLimits();
00144     }
00145 
00146     model_.propagateJointEffortToActuatorEffort();
00147     if (!model_.joint_states_.empty())
00148       mech_stats_publisher_->publish();
00149   }
00150 
00152   void shutdown()
00153   {
00154     for (boost::ptr_vector<Transmission>::iterator it = model_.transmissions_.begin();
00155          it != model_.transmissions_.end();
00156          ++it)
00157     {
00158       it->actuator_->command_.enable_ = false;
00159       it->actuator_->command_.effort_ = 0;
00160     }
00161   }
00162 
00163   ros::NodeHandle cm_node_;
00164   ros_ethercat_model::RobotState model_;
00165   EthercatHardware ec_;
00166   boost::scoped_ptr<MechStatsPublisher> mech_stats_publisher_;
00167 
00168   hardware_interface::JointStateInterface joint_state_interface_;
00169   hardware_interface::JointCommandInterface joint_command_interface_;
00170   hardware_interface::EffortJointInterface effort_joint_interface_;
00171   hardware_interface::PositionJointInterface position_joint_interface_;
00172 };
00173 
00174 #endif


ros_ethercat_model
Author(s): Manos Nikolaidis
autogenerated on Thu Aug 27 2015 14:47:12