mrp2_hardware_gazebo.h
Go to the documentation of this file.
00001 #ifndef MRP2_HARDWARE_GAZEBO_MRP2_HARDWARE_GAZEBO_H
00002 #define MRP2_HARDWARE_GAZEBO_MRP2_HARDWARE_GAZEBO_H
00003 
00004 #include <vector>
00005 #include <string>
00006 
00007 #include <control_toolbox/pid.h>
00008 
00009 #include <hardware_interface/robot_hw.h>
00010 #include <hardware_interface/joint_state_interface.h>
00011 #include <hardware_interface/joint_command_interface.h>
00012 #include <hardware_interface/imu_sensor_interface.h>
00013 #include <joint_limits_interface/joint_limits_interface.h>
00014 
00015 #include <pluginlib/class_list_macros.h>
00016 
00017 #include <gazebo_ros_control/robot_hw_sim.h>
00018 
00019 #include <angles/angles.h>
00020 
00021 #include <gazebo/gazebo.hh>
00022 #include <gazebo/physics/physics.hh>
00023 #include <gazebo/sensors/ImuSensor.hh>
00024 #include <gazebo/common/common.hh>
00025 
00026 namespace mrp2_hardware_gazebo
00027 {
00028 
00029 class Mrp2HardwareGazebo : public gazebo_ros_control::RobotHWSim
00030 {
00031 public:
00032 
00033   Mrp2HardwareGazebo();
00034 
00035   bool initSim(const std::string& robot_namespace,
00036       ros::NodeHandle model_nh,
00037       gazebo::physics::ModelPtr parent_model,
00038       const urdf::Model* const urdf_model,
00039       std::vector<transmission_interface::TransmissionInfo> transmissions);
00040   void readSim(ros::Time time, ros::Duration period);
00041   void writeSim(ros::Time time, ros::Duration period);
00042 
00043 
00044 private:
00045 
00046   unsigned int pos_n_dof_;
00047   unsigned int vel_n_dof_;
00048   unsigned int n_dof_;
00049 
00050   std::vector<std::string> transmission_names_;
00051 
00052   std::vector<double> jnt_pos_;
00053   std::vector<double> jnt_vel_;
00054   std::vector<double> jnt_eff_;
00055 
00056   std::vector<double> jnt_pos_cmd_;
00057   std::vector<double> jnt_pos_cmd_curr_; 
00058 
00059   std::vector<double> jnt_vel_cmd_;
00060 
00061   double base_orientation_[4];
00062   double base_ang_vel_[3];
00063   double base_lin_acc_[3];
00064 
00065   // Simulation-specific
00066   std::vector<gazebo::physics::JointPtr> sim_joints_;
00067   std::vector<gazebo::physics::JointPtr> pos_sim_joints_;
00068   std::vector<gazebo::physics::JointPtr> vel_sim_joints_;
00069   gazebo::sensors::ImuSensor* imu_sensor_;
00070 
00071   // Hardware interface: joints
00072   hardware_interface::JointStateInterface    jnt_state_interface_;
00073   hardware_interface::PositionJointInterface jnt_pos_cmd_interface_;
00074   hardware_interface::VelocityJointInterface jnt_vel_cmd_interface_;
00075 
00076   // Hardware interface: sensors
00077   hardware_interface::ImuSensorInterface     imu_sensor_interface_; // For inclinometer
00078 
00079   // Joint limits interface
00080   joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_limits_interface_;
00081   joint_limits_interface::VelocityJointSaturationInterface vel_jnt_limits_interface_;
00082 
00083   // PID controllers
00084   std::vector<control_toolbox::Pid> pids_;
00085 
00086   template <class T>
00087   std::string containerToString(const T& cont, const std::string& prefix)
00088   {
00089     std::stringstream ss;
00090     ss << prefix;
00091     std::copy(cont.begin(), --cont.end(), std::ostream_iterator<typename T::value_type>(ss, prefix.c_str()));
00092     ss << *(--cont.end());
00093     return ss.str();
00094   }
00095 
00096 };
00097 
00098 }
00099 
00100 #endif // MRP2_HARDWARE_GAZEBO_MRP2_HARDWARE_GAZEBO_H


mrp2_hardware_gazebo
Author(s): Akif Hacinecipoglu
autogenerated on Thu Jun 6 2019 20:36:46