reemc_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 REEMC_HARDWARE_GAZEBO_REEMC_HARDWARE_GAZEBO_H
00029 #define REEMC_HARDWARE_GAZEBO_REEMC_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/force_torque_sensor_interface.h>
00040 #include <hardware_interface/imu_sensor_interface.h>
00041 #include <joint_limits_interface/joint_limits_interface.h>
00042 #include <gazebo_ros_control/robot_hw_sim.h>
00043 
00044 #include <gazebo/physics/physics.hh>
00045 #include <gazebo/sensors/ImuSensor.hh>
00046 
00047 // Borrowed from pal_ros_control/pal_actuator_command_interface.h
00048 #include <hardware_interface/actuator_command_interface.h>
00049 
00050 namespace hardware_interface
00051 {
00053 class CurrentLimitActuatorInterface : public HardwareResourceManager<ActuatorHandle,DontClaimResources> {};
00054 }
00055 
00056 
00057 namespace reemc_hardware_gazebo
00058 {
00059 
00060 class ReemcHardwareGazebo : public gazebo_ros_control::RobotHWSim
00061 {
00062 public:
00063 
00064   ReemcHardwareGazebo();
00065 
00066   // Simulation-specific
00067   bool initSim(const std::string& robot_ns,
00068                ros::NodeHandle nh,
00069                gazebo::physics::ModelPtr model,
00070                const urdf::Model* const urdf_model,
00071                std::vector<transmission_interface::TransmissionInfo> transmissions);
00072   void readSim(ros::Time time, ros::Duration period);
00073   void writeSim(ros::Time time, ros::Duration period);
00074 
00075 private:
00076 
00077   // Raw data
00078   unsigned int n_dof_;
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_curr_limit_cmd_;
00086   std::vector<double> jnt_max_effort_;
00087 
00088   double left_force_[3];
00089   double left_torque_[3];
00090   double right_force_[3];
00091   double right_torque_[3];
00092 
00093   double base_orientation_[4];
00094   double base_ang_vel_[3];
00095   double base_lin_acc_[3];
00096 
00097   // Simulation-specific
00098   std::vector<gazebo::physics::JointPtr> sim_joints_;
00099   gazebo::physics::JointPtr left_ankle_;
00100   gazebo::physics::JointPtr right_ankle_;
00101   boost::shared_ptr<gazebo::sensors::ImuSensor> imu_sensor_;
00102 
00103   // Hardware interface: joints
00104   hardware_interface::JointStateInterface    jnt_state_interface_;
00105   hardware_interface::PositionJointInterface jnt_pos_cmd_interface_;
00106   hardware_interface::ActuatorStateInterface    act_state_interface_;
00107   hardware_interface::CurrentLimitActuatorInterface jnt_curr_limit_cmd_interface_;
00108 
00109   // Hardware interface: sensors
00110   hardware_interface::ForceTorqueSensorInterface ft_sensor_interface_;
00111   hardware_interface::ImuSensorInterface         imu_sensor_interface_;
00112 
00113   // Joint limits interface
00114   joint_limits_interface::PositionJointSoftLimitsInterface jnt_limits_interface_;
00115 
00116   // PID controllers
00117   std::vector<control_toolbox::Pid> pids_;
00118 };
00119 
00120 }
00121 
00122 #endif // REEMC_HARDWARE_GAZEBO_REEMC_HARDWARE_GAZEBO_H


reemc_hardware_gazebo
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Aug 27 2015 14:40:15