Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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
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
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_;
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
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
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
00105 hardware_interface::ImuSensorInterface imu_sensor_interface_;
00106
00107
00108 joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_limits_interface_;
00109 joint_limits_interface::VelocityJointSaturationInterface vel_jnt_limits_interface_;
00110
00111
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