pmb2_hardware_gazebo.h
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00028 #ifndef PMB2_HARDWARE_GAZEBO_PMB2_HARDWARE_GAZEBO_H
00029 #define PMB2_HARDWARE_GAZEBO_PMB2_HARDWARE_GAZEBO_H
00030 
00031 #include <vector>
00032 #include <string>
00033 
00034 #include <control_toolbox/pid.h>
00035 
00036 #include <hardware_interface/robot_hw.h>
00037 #include <hardware_interface/joint_state_interface.h>
00038 #include <hardware_interface/joint_command_interface.h>
00039 #include <hardware_interface/imu_sensor_interface.h>
00040 #include <joint_limits_interface/joint_limits_interface.h>
00041 
00042 #include <pluginlib/class_list_macros.h>
00043 
00044 #include <gazebo_ros_control/robot_hw_sim.h>
00045 
00046 #include <angles/angles.h>
00047 
00048 #include <gazebo/gazebo.hh>
00049 #include <gazebo/physics/physics.hh>
00050 #include <gazebo/sensors/ImuSensor.hh>
00051 #include <gazebo/common/common.hh>
00052 
00053 namespace pmb2_hardware_gazebo
00054 {
00055 
00056 class Pmb2HardwareGazebo : public gazebo_ros_control::RobotHWSim
00057 {
00058 public:
00059 
00060   Pmb2HardwareGazebo();
00061 
00062   // Simulation-specific
00063   bool initSim(const std::string& robot_namespace,
00064       ros::NodeHandle model_nh,
00065       gazebo::physics::ModelPtr parent_model,
00066       const urdf::Model* const urdf_model,
00067       std::vector<transmission_interface::TransmissionInfo> transmissions);
00068   void readSim(ros::Time time, ros::Duration period);
00069   void writeSim(ros::Time time, ros::Duration period);
00070 
00071 
00072 private:
00073   // Raw data
00074   unsigned int pos_n_dof_;
00075   unsigned int vel_n_dof_;
00076   unsigned int n_dof_;
00077 
00078   std::vector<std::string> transmission_names_;
00079 
00080   std::vector<double> jnt_pos_;
00081   std::vector<double> jnt_vel_;
00082   std::vector<double> jnt_eff_;
00083 
00084   std::vector<double> jnt_pos_cmd_;
00085   std::vector<double> jnt_pos_cmd_curr_; // NOTE: This is the same as jnt_pos_ but only with the joints in pos_sim_joints_. Needs cleaner implementation
00086 
00087   std::vector<double> jnt_vel_cmd_;
00088 
00089   double base_orientation_[4];
00090   double base_ang_vel_[3];
00091   double base_lin_acc_[3];
00092 
00093   // Simulation-specific
00094   std::vector<gazebo::physics::JointPtr> sim_joints_;
00095   std::vector<gazebo::physics::JointPtr> pos_sim_joints_;
00096   std::vector<gazebo::physics::JointPtr> vel_sim_joints_;
00097   gazebo::sensors::ImuSensor* imu_sensor_;
00098 
00099   // Hardware interface: joints
00100   hardware_interface::JointStateInterface    jnt_state_interface_;
00101   hardware_interface::PositionJointInterface jnt_pos_cmd_interface_;
00102   hardware_interface::VelocityJointInterface jnt_vel_cmd_interface_;
00103 
00104   // Hardware interface: sensors
00105   hardware_interface::ImuSensorInterface     imu_sensor_interface_; // For inclinometer
00106 
00107   // Joint limits interface
00108   joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_limits_interface_;
00109   joint_limits_interface::VelocityJointSaturationInterface vel_jnt_limits_interface_;
00110 
00111   // PID controllers
00112   std::vector<control_toolbox::Pid> pids_;
00113 
00114   template <class T>
00115   std::string containerToString(const T& cont, const std::string& prefix)
00116   {
00117     std::stringstream ss;
00118     ss << prefix;
00119     std::copy(cont.begin(), --cont.end(), std::ostream_iterator<typename T::value_type>(ss, prefix.c_str()));
00120     ss << *(--cont.end());
00121     return ss.str();
00122   }
00123 
00124 };
00125 
00126 }
00127 
00128 #endif // PMB2_HARDWARE_GAZEBO_PMB2_HARDWARE_GAZEBO_H


pmb2_hardware_gazebo
Author(s): Enrique Fernandez
autogenerated on Wed Aug 26 2015 15:32:19