robot_state_interface.hpp
Go to the documentation of this file.
00001 /*
00002  * robot_state.hpp
00003  *
00004  *  Created on: 19 Feb 2016
00005  *      Author: Toni Oliver
00006  *
00007  * Software License Agreement (BSD License)
00008  *
00009  *  Copyright (c) 2016, 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_ROBOT_STATE_INTERFACE_HPP
00041 #define ROS_ETHERCAT_MODEL_ROBOT_STATE_INTERFACE_HPP
00042 
00043 #include <hardware_interface/internal/hardware_resource_manager.h>
00044 #include "ros_ethercat_model/robot_state.hpp"
00045 
00046 
00047 namespace ros_ethercat_model
00048 {
00049 
00051 class RobotStateHandle
00052 {
00053 public:
00054   RobotStateHandle() : name_(), state_(0) {}
00055 
00060   RobotStateHandle(const std::string& name, RobotState* state)
00061     : name_(name), state_(state)
00062   {
00063     if (!state)
00064     {
00065       throw hardware_interface::HardwareInterfaceException("Cannot create handle '" + name + "'. RobtState data pointer is null.");
00066     }
00067   }
00068 
00069   std::string getName() const {return name_;}
00070   RobotState* getState() const {assert(state_); return state_;}
00071 
00072 private:
00073   std::string name_;
00074   RobotState* state_;
00075 };
00076 
00082 class RobotStateInterface : public hardware_interface::HardwareResourceManager<RobotStateHandle> {};
00083 
00084 }
00085 
00086 #endif


ros_ethercat_model
Author(s): Manos Nikolaidis
autogenerated on Thu Jul 4 2019 20:01:55